Compare commits

...

4 Commits

Author SHA1 Message Date
fbf0a87d8d add schematic and PCB 2025-04-04 18:39:40 +03:00
8bb8f93f83 forgot to add testDev in last commit 2025-04-04 12:22:01 +03:00
6adf025f62 fix readme 2025-04-04 12:03:55 +03:00
f46185feaf encoders works fine 2025-04-04 11:56:37 +03:00
49 changed files with 146651 additions and 357 deletions

View File

@ -1,5 +1,124 @@
Get data from 2 encoders by BISS-C protocol Get data from 2 encoders by BISS-C protocol
=========================================== ===========================================
This device works with two BISS-C encoders (resolution from 8 to 32 bit).
If you want to test readout from device, run `./testDev /dev/encoder_X0` or `./testDev /dev/encoder_X0`.
## Encoder cable pinout:
* 1 - NC or shield
* 2 - CLK_A - positive of SSI clock out
* 3 - CLC_B - negative of SSI clock out
* 4 - NC or shield
* 5 - +5V - 5V power for sensor (at least 250mA)
* 6 - DATA_A - positive of data in
* 7 - DATA_B - negative of data in
* 8 - NC
* 9 - Gnd - common ground
## Device interfaces
After connection you will see device 0483:5740 with three CDC interfaces. Each interface
have its own `iInterface` field, by default they are:
* encoder_cmd - configure/command/debugging interface
* encoder_X - X sensor output
* encoder_Y - Y sensor output
Add to udev-rules file `99-myHW.rules` which will create symlinks to each interface in `/dev/` directory.
You can change all three `iInterface` values and store them in device' flash memory.
The readout of encoders depends on settings. If you save in flash `autom=1`, readout of both encoders
will repeat each `amperiod` milliseconds. Also you always can ask for readout sending any '\n'-terminated
data into encoder's interface or running commands `readenc`, `readX` or `readY` in command interface.
## Protocol
The device have simple text protocol, each text string should be closed by '\n'.
Base format is 'param [ = value]', where 'param' could be command to run some procedure
or getter, 'value' is setter.
Answer for all getters is 'param=value'. Here are answers for setters and procedures:
* OK - all OK
* FAIL - procedure failed to run
* BADCMD - your entered wrong command
* BADPAR - parameter of setter is out of allowable range
Some procedures (like 'help' or 'readenc') returns a lot of data after calling.
### Base commands on command interface
These are commands for directrly work with SPI interfaces:
* readenc - read both encoders once
* readX - read X encoder once
* readY - read Y encoder once
* help - show full help
* reset - reset MCU
* spideinit - deinit SPI
* spiinit - init SPI
* spistat - get status of both SPI interfaces
### Configuration commands
This set of commands allows to change current configuration (remember: each time SPI configuration changes
you need to run `spiinit`) and store it into flash memory.
* autom - turn on or off automonitoring
* amperiod - period of monitoring, 1..255 milliseconds
* BR - change SPI BR register (1 - 18MHz ... 7 - 281kHz)
* CPHA - change CPHA value (0/1)
* CPOL - change CPOL value (0/1)
* dumpconf - dump current configuration
* encbits - set encoder data bits amount (26/32)
* encbufsz - change encoder auxiliary buffer size (8..32 bytes)
* erasestorage - erase full storage or current page (=n)
* maxzeros - maximal amount of zeros in preamble
* minzeros - minimal amount of zeros in preamble
* setiface1 - set name of first (command) interface
* setiface2 - set name of second (axis X) interface
* setiface3 - set name of third (axis Y) interface
* storeconf - store configuration in flash memory
Here is example of default configuration ouput (`dumpconf`):
```
userconf_sz=108
currentconfidx=-1
setiface1=
setiface2=
setiface3=
autom=0
amperiod=1
BR=4
CPHA=0
CPOL=1
encbits=26
encbufsz=12
maxzeros=50
minzeros=4
```
`userconf_sz` is some type of "magick sequence" to find start of last record in flash memory.
`currentconfidx` shows number of record (-1 means that the storage is empty and you see default values).
Empty field of `setifaceX` means default interface name.
### Debugging commands
Some of these commands could be usefull when you're trying to play with settings or want to measure maximal
readout speed for encoders (when each reading starts immediately after parsing previous result).
* dummy - dummy integer setter/getter
* fin - reinit flash (e.g. to restore last configuration)
* sendx - send text string to X encoder's terminal
* sendy - send text string to Y encoder's terminal
* testx - test X-axis throughput
* testy - test Y-axis throughput
tl;dr

View File

@ -17,16 +17,14 @@
*/ */
#include "bissC.h" #include "bissC.h"
#include "usb_dev.h" #include "flash.h"
#ifdef EBUG #ifdef EBUG
#include "strfunc.h" #include "strfunc.h"
#endif #endif
#include "flash.h" #include "spi.h"
#include "usb_dev.h"
#define MAX_BITSTREAM_UINTS 4 // 4 * 32 = 128 bits capacity #define MAX_BITSTREAM_UINTS (ENCODER_BUFSZ_MAX / 4) // ENCODER_BUFSZ_MAX bits capacity
// min/max zeros before preambule
#define MINZEROS 4
#define MAXZEROS 40
static uint32_t bitstream[MAX_BITSTREAM_UINTS] = {0}; static uint32_t bitstream[MAX_BITSTREAM_UINTS] = {0};
@ -50,11 +48,6 @@ static void bytes_to_bitstream(const uint8_t *bytes, uint32_t num_bytes, uint32_
} }
} }
} }
/* Store remaining bits if any
if(*num_bits % 32 != 0){
current <<= (32 - (*num_bits % 32));
bitstream[pos] = current;
}*/
} }
// Compute CRC-6 using polynomial x^6 + x + 1 // Compute CRC-6 using polynomial x^6 + x + 1
@ -102,7 +95,7 @@ BiSS_Frame parse_biss_frame(const uint8_t *bytes, uint32_t num_bytes){
if(!curbit){ if(!curbit){
zero_count++; zero_count++;
}else{ }else{
if(zero_count >= MINZEROS && zero_count <= MAXZEROS){ if(zero_count >= the_conf.minzeros && zero_count <= the_conf.maxzeros){
if((i + 1) < num_bits && !get_bit(i + 1)){ if((i + 1) < num_bits && !get_bit(i + 1)){
data_start = i + 2; data_start = i + 2;
found = 1; found = 1;

View File

@ -20,6 +20,11 @@
#include <stdint.h> #include <stdint.h>
#include "spi.h"
#if ENCRESOL_MAX > 32
#error "Change full code. Current don't support more than 32 bits of encoder resolution."
#endif
typedef struct { typedef struct {
uint32_t data; // 26/32/36-bit data uint32_t data; // 26/32/36-bit data
uint8_t error : 1; // error flag (0 - error: bad value or high temperature) uint8_t error : 1; // error flag (0 - error: bad value or high temperature)

Binary file not shown.

View File

@ -1,6 +1,6 @@
<?xml version="1.0" encoding="UTF-8"?> <?xml version="1.0" encoding="UTF-8"?>
<!DOCTYPE QtCreatorProject> <!DOCTYPE QtCreatorProject>
<!-- Written by QtCreator 15.0.1, 2025-04-02T14:36:26. --> <!-- Written by QtCreator 15.0.1, 2025-04-02T18:29:56. -->
<qtcreator> <qtcreator>
<data> <data>
<variable>EnvironmentId</variable> <variable>EnvironmentId</variable>

View File

@ -33,7 +33,11 @@ user_conf the_conf = {
.userconf_sz = sizeof(user_conf), .userconf_sz = sizeof(user_conf),
.flags.CPOL = 1, .flags.CPOL = 1,
.flags.BR = 4, .flags.BR = 4,
.encbits = 26 .encbits = 26,
.encbufsz = 12,
.minzeros = 4,
.maxzeros = 50,
.monittime = 1,
}; };
int currentconfidx = -1; // index of current configuration int currentconfidx = -1; // index of current configuration

View File

@ -27,10 +27,17 @@
// maximal size (in letters) of iInterface for settings // maximal size (in letters) of iInterface for settings
#define MAX_IINTERFACE_SZ (16) #define MAX_IINTERFACE_SZ (16)
// min/max zeros before preambule
#define MINZEROS_MIN 2
#define MINZEROS_MAX 60
#define MAXZEROS_MIN 4
#define MAXZEROS_MAX 120
typedef struct{ typedef struct{
uint8_t CPOL : 1; uint8_t CPOL : 1;
uint8_t CPHA : 1; uint8_t CPHA : 1;
uint8_t BR : 3; uint8_t BR : 3;
uint8_t monit: 1; // auto monitoring of encoder each `monittime` milliseconds
} flags_t; } flags_t;
/* /*
@ -40,8 +47,12 @@ typedef struct __attribute__((packed, aligned(4))){
uint16_t userconf_sz; // "magick number" uint16_t userconf_sz; // "magick number"
uint16_t iInterface[bTotNumEndpoints][MAX_IINTERFACE_SZ]; // hryunikod! uint16_t iInterface[bTotNumEndpoints][MAX_IINTERFACE_SZ]; // hryunikod!
uint8_t iIlengths[bTotNumEndpoints]; uint8_t iIlengths[bTotNumEndpoints];
flags_t flags; // flags: CPOL, CPHA etc
uint8_t encbits; // encoder bits: 26 or 32 uint8_t encbits; // encoder bits: 26 or 32
uint8_t encbufsz; // encoder buffer size (up to ENCODER_BUFSZ_MAX)
uint8_t minzeros; // min/max zeros in preamble when searching start of record
uint8_t maxzeros;
uint8_t monittime; // auto monitoring period (ms)
flags_t flags; // flags: CPOL, CPHA etc
} user_conf; } user_conf;
extern user_conf the_conf; extern user_conf the_conf;

View File

@ -0,0 +1,27 @@
"Reference","Value","Datasheet","Footprint","Qty","DNP"
"C1,C2,C6,C7,C8,C9,C10,C11,C12,C15,C16,C20,C21","0.1","~","Capacitor_SMD:C_0603_1608Metric_Pad1.08x0.95mm_HandSolder","13",""
"C3","22u","~","Capacitor_SMD:C_0805_2012Metric_Pad1.18x1.45mm_HandSolder","1",""
"C4,C5","12","~","Capacitor_SMD:C_0603_1608Metric_Pad1.08x0.95mm_HandSolder","2",""
"C13,C14,C22,C23","1u","~","Capacitor_SMD:C_0805_2012Metric_Pad1.18x1.45mm_HandSolder","4",""
"C17,C18,C19","0.47","~","Capacitor_SMD:C_0805_2012Metric_Pad1.18x1.45mm_HandSolder","3",""
"D1,D2,D7","1N5817","~","Diode_SMD:D_SMA-SMB_Universal_Handsoldering","3",""
"D3,D4,D8,D9","SM712_SOT23","https://www.littelfuse.com/~/media/electronics/datasheets/tvs_diode_arrays/littelfuse_tvs_diode_array_sm712_datasheet.pdf.pdf","Package_TO_SOT_SMD:SOT-23","4",""
"D5,D6","SMAJ15CA","https://www.littelfuse.com/media?resourcetype=datasheets&itemid=75e32973-b177-4ee3-a0ff-cedaf1abdb93&filename=smaj-datasheet","Diode_SMD:D_SMA","2",""
"F1,F2","0.5A","~","Fuse:Fuse_1206_3216Metric","2",""
"J1","Screw_Terminal_01x02","~","TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2_1x02_P5.00mm_Horizontal","1",""
"J2","USB_B","~","Connector_USB:USB_B_OST_USB-B1HSxx_Horizontal","1",""
"J5,J6,J7,J11","HOLE","~","MountingHole:MountingHole_3.2mm_M3","4",""
"J8,J10","SSI/422","~","my_footprints:DSUB-9_Female_Horizontal_P2.77x2.84mm_EdgePinOffset4.94mm_Housed_MountingHolesOffset7.48mm","2",""
"J9","4P4C","~","Connector_RJ:RJ9_Evercom_5301-440xxx_Horizontal","1",""
"Q1","DTA114Y","","Package_TO_SOT_SMD:SOT-323_SC-70_Handsoldering","1",""
"Q2,Q3","B0505S-2W","","my_footprints:B0505S-2W","2",""
"R1,R2,R3","22","~","Resistor_SMD:R_0603_1608Metric_Pad0.98x0.95mm_HandSolder","3",""
"R4","1k5","~","Resistor_SMD:R_0603_1608Metric_Pad0.98x0.95mm_HandSolder","1",""
"R5","1k","~","Resistor_SMD:R_0603_1608Metric_Pad0.98x0.95mm_HandSolder","1",""
"R6","10k","~","Resistor_SMD:R_0603_1608Metric_Pad0.98x0.95mm_HandSolder","1",""
"U1","LM1117MP-3.3","http://www.ti.com/lit/ds/symlink/lm1117.pdf","Package_TO_SOT_SMD:SOT-223-3_TabPin2","1",""
"U2","USBLC6-2SC6","https://www.st.com/resource/en/datasheet/usblc6-2.pdf","Package_TO_SOT_SMD:SOT-23-6","1",""
"U3","STM32F103C8Tx","https://www.st.com/resource/en/datasheet/stm32f103c8.pdf","Package_QFP:LQFP-48_7x7mm_P0.5mm","1",""
"U4,U6","ISO3086","","Package_SO:SOIC-16W_7.5x10.3mm_P1.27mm","2",""
"U5","MAX3232","https://datasheets.maximintegrated.com/en/ds/MAX3222-MAX3241.pdf","Package_SO:SOIC-16_3.9x9.9mm_P1.27mm","1",""
"Y1","8MHz","~","Crystal:Crystal_HC49-U_Vertical","1",""
1 Reference Value Datasheet Footprint Qty DNP
2 C1,C2,C6,C7,C8,C9,C10,C11,C12,C15,C16,C20,C21 0.1 ~ Capacitor_SMD:C_0603_1608Metric_Pad1.08x0.95mm_HandSolder 13
3 C3 22u ~ Capacitor_SMD:C_0805_2012Metric_Pad1.18x1.45mm_HandSolder 1
4 C4,C5 12 ~ Capacitor_SMD:C_0603_1608Metric_Pad1.08x0.95mm_HandSolder 2
5 C13,C14,C22,C23 1u ~ Capacitor_SMD:C_0805_2012Metric_Pad1.18x1.45mm_HandSolder 4
6 C17,C18,C19 0.47 ~ Capacitor_SMD:C_0805_2012Metric_Pad1.18x1.45mm_HandSolder 3
7 D1,D2,D7 1N5817 ~ Diode_SMD:D_SMA-SMB_Universal_Handsoldering 3
8 D3,D4,D8,D9 SM712_SOT23 https://www.littelfuse.com/~/media/electronics/datasheets/tvs_diode_arrays/littelfuse_tvs_diode_array_sm712_datasheet.pdf.pdf Package_TO_SOT_SMD:SOT-23 4
9 D5,D6 SMAJ15CA https://www.littelfuse.com/media?resourcetype=datasheets&itemid=75e32973-b177-4ee3-a0ff-cedaf1abdb93&filename=smaj-datasheet Diode_SMD:D_SMA 2
10 F1,F2 0.5A ~ Fuse:Fuse_1206_3216Metric 2
11 J1 Screw_Terminal_01x02 ~ TerminalBlock_Phoenix:TerminalBlock_Phoenix_MKDS-1,5-2_1x02_P5.00mm_Horizontal 1
12 J2 USB_B ~ Connector_USB:USB_B_OST_USB-B1HSxx_Horizontal 1
13 J5,J6,J7,J11 HOLE ~ MountingHole:MountingHole_3.2mm_M3 4
14 J8,J10 SSI/422 ~ my_footprints:DSUB-9_Female_Horizontal_P2.77x2.84mm_EdgePinOffset4.94mm_Housed_MountingHolesOffset7.48mm 2
15 J9 4P4C ~ Connector_RJ:RJ9_Evercom_5301-440xxx_Horizontal 1
16 Q1 DTA114Y Package_TO_SOT_SMD:SOT-323_SC-70_Handsoldering 1
17 Q2,Q3 B0505S-2W my_footprints:B0505S-2W 2
18 R1,R2,R3 22 ~ Resistor_SMD:R_0603_1608Metric_Pad0.98x0.95mm_HandSolder 3
19 R4 1k5 ~ Resistor_SMD:R_0603_1608Metric_Pad0.98x0.95mm_HandSolder 1
20 R5 1k ~ Resistor_SMD:R_0603_1608Metric_Pad0.98x0.95mm_HandSolder 1
21 R6 10k ~ Resistor_SMD:R_0603_1608Metric_Pad0.98x0.95mm_HandSolder 1
22 U1 LM1117MP-3.3 http://www.ti.com/lit/ds/symlink/lm1117.pdf Package_TO_SOT_SMD:SOT-223-3_TabPin2 1
23 U2 USBLC6-2SC6 https://www.st.com/resource/en/datasheet/usblc6-2.pdf Package_TO_SOT_SMD:SOT-23-6 1
24 U3 STM32F103C8Tx https://www.st.com/resource/en/datasheet/stm32f103c8.pdf Package_QFP:LQFP-48_7x7mm_P0.5mm 1
25 U4,U6 ISO3086 Package_SO:SOIC-16W_7.5x10.3mm_P1.27mm 2
26 U5 MAX3232 https://datasheets.maximintegrated.com/en/ds/MAX3222-MAX3241.pdf Package_SO:SOIC-16_3.9x9.9mm_P1.27mm 1
27 Y1 8MHz ~ Crystal:Crystal_HC49-U_Vertical 1

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,132 @@
{
"board": {
"active_layer": 0,
"active_layer_preset": "All Layers",
"auto_track_width": false,
"hidden_netclasses": [],
"hidden_nets": [],
"high_contrast_mode": 0,
"net_color_mode": 1,
"opacity": {
"images": 0.6,
"pads": 1.0,
"shapes": 1.0,
"tracks": 1.0,
"vias": 1.0,
"zones": 0.6
},
"prototype_zone_fills": false,
"selection_filter": {
"dimensions": true,
"footprints": true,
"graphics": true,
"keepouts": true,
"lockedItems": true,
"otherItems": true,
"pads": true,
"text": true,
"tracks": true,
"vias": true,
"zones": true
},
"visible_items": [
"vias",
"footprint_text",
"footprint_anchors",
"ratsnest",
"grid",
"footprints_front",
"footprints_back",
"footprint_values",
"footprint_references",
"tracks",
"drc_errors",
"drawing_sheet",
"bitmaps",
"pads",
"zones",
"drc_warnings",
"locked_item_shadows",
"conflict_shadows",
"shapes"
],
"visible_layers": "ffffffff_ffffffff_ffffffff_ffffffff",
"zone_display_mode": 0
},
"git": {
"repo_password": "",
"repo_type": "",
"repo_username": "",
"ssh_key": ""
},
"meta": {
"filename": "encoder.kicad_prl",
"version": 5
},
"net_inspector_panel": {
"col_hidden": [
false,
false,
false,
false,
false,
false,
false,
false,
false,
false
],
"col_order": [
0,
1,
2,
3,
4,
5,
6,
7,
8,
9
],
"col_widths": [
0,
0,
0,
0,
0,
0,
0,
0,
0,
0
],
"custom_group_rules": [],
"expanded_rows": [],
"filter_by_net_name": true,
"filter_by_netclass": true,
"filter_text": "",
"group_by_constraint": false,
"group_by_netclass": false,
"show_unconnected_nets": false,
"show_zero_pad_nets": false,
"sort_ascending": true,
"sorting_column": 0
},
"open_jobsets": [],
"project": {
"files": []
},
"schematic": {
"selection_filter": {
"graphics": true,
"images": true,
"labels": true,
"lockedItems": false,
"otherItems": true,
"pins": true,
"symbols": true,
"text": true,
"wires": true
}
}
}

View File

@ -0,0 +1,685 @@
{
"board": {
"3dviewports": [],
"design_settings": {
"defaults": {
"apply_defaults_to_fp_fields": false,
"apply_defaults_to_fp_shapes": false,
"apply_defaults_to_fp_text": false,
"board_outline_line_width": 0.05,
"copper_line_width": 0.2,
"copper_text_italic": false,
"copper_text_size_h": 1.5,
"copper_text_size_v": 1.5,
"copper_text_thickness": 0.3,
"copper_text_upright": false,
"courtyard_line_width": 0.05,
"dimension_precision": 2,
"dimension_units": 2,
"dimensions": {
"arrow_length": 1270000,
"extension_offset": 500000,
"keep_text_aligned": true,
"suppress_zeroes": true,
"text_position": 0,
"units_format": 0
},
"fab_line_width": 0.1,
"fab_text_italic": false,
"fab_text_size_h": 1.0,
"fab_text_size_v": 1.0,
"fab_text_thickness": 0.15,
"fab_text_upright": false,
"other_line_width": 0.1,
"other_text_italic": false,
"other_text_size_h": 1.0,
"other_text_size_v": 1.0,
"other_text_thickness": 0.15,
"other_text_upright": false,
"pads": {
"drill": 0.8,
"height": 1.27,
"width": 2.54
},
"silk_line_width": 0.1,
"silk_text_italic": false,
"silk_text_size_h": 1.0,
"silk_text_size_v": 1.0,
"silk_text_thickness": 0.1,
"silk_text_upright": false,
"zones": {
"min_clearance": 0.0
}
},
"diff_pair_dimensions": [
{
"gap": 0.0,
"via_gap": 0.0,
"width": 0.0
}
],
"drc_exclusions": [],
"meta": {
"version": 2
},
"rule_severities": {
"annular_width": "error",
"clearance": "error",
"connection_width": "warning",
"copper_edge_clearance": "error",
"copper_sliver": "warning",
"courtyards_overlap": "error",
"creepage": "error",
"diff_pair_gap_out_of_range": "error",
"diff_pair_uncoupled_length_too_long": "error",
"drill_out_of_range": "error",
"duplicate_footprints": "warning",
"extra_footprint": "warning",
"footprint": "error",
"footprint_filters_mismatch": "ignore",
"footprint_symbol_mismatch": "warning",
"footprint_type_mismatch": "ignore",
"hole_clearance": "error",
"hole_to_hole": "warning",
"holes_co_located": "warning",
"invalid_outline": "error",
"isolated_copper": "warning",
"item_on_disabled_layer": "error",
"items_not_allowed": "error",
"length_out_of_range": "error",
"lib_footprint_issues": "warning",
"lib_footprint_mismatch": "warning",
"malformed_courtyard": "error",
"microvia_drill_out_of_range": "error",
"mirrored_text_on_front_layer": "warning",
"missing_courtyard": "ignore",
"missing_footprint": "warning",
"net_conflict": "warning",
"nonmirrored_text_on_back_layer": "warning",
"npth_inside_courtyard": "ignore",
"padstack": "warning",
"pth_inside_courtyard": "ignore",
"shorting_items": "error",
"silk_edge_clearance": "ignore",
"silk_over_copper": "warning",
"silk_overlap": "warning",
"skew_out_of_range": "error",
"solder_mask_bridge": "error",
"starved_thermal": "error",
"text_height": "warning",
"text_on_edge_cuts": "error",
"text_thickness": "warning",
"through_hole_pad_without_hole": "error",
"too_many_vias": "error",
"track_angle": "error",
"track_dangling": "warning",
"track_segment_length": "error",
"track_width": "error",
"tracks_crossing": "error",
"unconnected_items": "error",
"unresolved_variable": "error",
"via_dangling": "warning",
"zones_intersect": "error"
},
"rules": {
"max_error": 0.005,
"min_clearance": 0.2,
"min_connection": 0.2,
"min_copper_edge_clearance": 1.0,
"min_groove_width": 0.0,
"min_hole_clearance": 0.25,
"min_hole_to_hole": 0.3,
"min_microvia_diameter": 0.2,
"min_microvia_drill": 0.1,
"min_resolved_spokes": 2,
"min_silk_clearance": 0.0,
"min_text_height": 0.8,
"min_text_thickness": 0.08,
"min_through_hole_diameter": 0.4,
"min_track_width": 0.2,
"min_via_annular_width": 0.1,
"min_via_diameter": 0.6,
"solder_mask_to_copper_clearance": 0.0,
"use_height_for_length_calcs": true
},
"teardrop_options": [
{
"td_onpthpad": true,
"td_onroundshapesonly": false,
"td_onsmdpad": true,
"td_ontrackend": false,
"td_onvia": true
}
],
"teardrop_parameters": [
{
"td_allow_use_two_tracks": true,
"td_curve_segcount": 0,
"td_height_ratio": 1.0,
"td_length_ratio": 0.5,
"td_maxheight": 2.0,
"td_maxlen": 1.0,
"td_on_pad_in_zone": false,
"td_target_name": "td_round_shape",
"td_width_to_size_filter_ratio": 0.9
},
{
"td_allow_use_two_tracks": true,
"td_curve_segcount": 0,
"td_height_ratio": 1.0,
"td_length_ratio": 0.5,
"td_maxheight": 2.0,
"td_maxlen": 1.0,
"td_on_pad_in_zone": false,
"td_target_name": "td_rect_shape",
"td_width_to_size_filter_ratio": 0.9
},
{
"td_allow_use_two_tracks": true,
"td_curve_segcount": 0,
"td_height_ratio": 1.0,
"td_length_ratio": 0.5,
"td_maxheight": 2.0,
"td_maxlen": 1.0,
"td_on_pad_in_zone": false,
"td_target_name": "td_track_end",
"td_width_to_size_filter_ratio": 0.9
}
],
"track_widths": [
0.0,
0.2,
0.25,
0.5,
1.0
],
"tuning_pattern_settings": {
"diff_pair_defaults": {
"corner_radius_percentage": 80,
"corner_style": 1,
"max_amplitude": 1.0,
"min_amplitude": 0.2,
"single_sided": false,
"spacing": 1.0
},
"diff_pair_skew_defaults": {
"corner_radius_percentage": 80,
"corner_style": 1,
"max_amplitude": 1.0,
"min_amplitude": 0.2,
"single_sided": false,
"spacing": 0.6
},
"single_track_defaults": {
"corner_radius_percentage": 80,
"corner_style": 1,
"max_amplitude": 1.0,
"min_amplitude": 0.2,
"single_sided": false,
"spacing": 0.6
}
},
"via_dimensions": [
{
"diameter": 0.0,
"drill": 0.0
},
{
"diameter": 0.8,
"drill": 0.4
},
{
"diameter": 1.0,
"drill": 0.6
},
{
"diameter": 1.2,
"drill": 0.8
}
],
"zones_allow_external_fillets": false
},
"ipc2581": {
"dist": "",
"distpn": "",
"internal_id": "",
"mfg": "",
"mpn": ""
},
"layer_pairs": [],
"layer_presets": [],
"viewports": []
},
"boards": [],
"component_class_settings": {
"assignments": [],
"meta": {
"version": 0
},
"sheet_component_classes": {
"enabled": false
}
},
"cvpcb": {
"equivalence_files": []
},
"erc": {
"erc_exclusions": [],
"meta": {
"version": 0
},
"pin_map": [
[
0,
0,
0,
0,
0,
0,
1,
0,
0,
0,
0,
2
],
[
0,
2,
0,
1,
0,
0,
1,
0,
2,
2,
2,
2
],
[
0,
0,
0,
0,
0,
0,
1,
0,
1,
0,
1,
2
],
[
0,
1,
0,
0,
0,
0,
1,
1,
2,
1,
1,
2
],
[
0,
0,
0,
0,
0,
0,
1,
0,
0,
0,
0,
2
],
[
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
0,
2
],
[
1,
1,
1,
1,
1,
0,
1,
1,
1,
1,
1,
2
],
[
0,
0,
0,
1,
0,
0,
1,
0,
0,
0,
0,
2
],
[
0,
2,
1,
2,
0,
0,
1,
0,
2,
2,
2,
2
],
[
0,
2,
0,
1,
0,
0,
1,
0,
2,
0,
0,
2
],
[
0,
2,
1,
1,
0,
0,
1,
0,
2,
0,
0,
2
],
[
2,
2,
2,
2,
2,
2,
2,
2,
2,
2,
2,
2
]
],
"rule_severities": {
"bus_definition_conflict": "error",
"bus_entry_needed": "error",
"bus_to_bus_conflict": "error",
"bus_to_net_conflict": "error",
"conflicting_netclasses": "error",
"different_unit_footprint": "error",
"different_unit_net": "error",
"duplicate_reference": "error",
"duplicate_sheet_names": "error",
"endpoint_off_grid": "ignore",
"extra_units": "error",
"footprint_filter": "ignore",
"footprint_link_issues": "warning",
"four_way_junction": "ignore",
"global_label_dangling": "warning",
"hier_label_mismatch": "error",
"label_dangling": "error",
"label_multiple_wires": "warning",
"lib_symbol_issues": "warning",
"lib_symbol_mismatch": "warning",
"missing_bidi_pin": "warning",
"missing_input_pin": "warning",
"missing_power_pin": "error",
"missing_unit": "warning",
"multiple_net_names": "warning",
"net_not_bus_member": "warning",
"no_connect_connected": "warning",
"no_connect_dangling": "warning",
"pin_not_connected": "error",
"pin_not_driven": "error",
"pin_to_pin": "error",
"power_pin_not_driven": "error",
"same_local_global_label": "warning",
"similar_label_and_power": "warning",
"similar_labels": "warning",
"similar_power": "warning",
"simulation_model_issue": "ignore",
"single_global_label": "ignore",
"unannotated": "error",
"unconnected_wire_endpoint": "warning",
"unit_value_mismatch": "error",
"unresolved_variable": "error",
"wire_dangling": "error"
}
},
"libraries": {
"pinned_footprint_libs": [
"Connector_minidin"
],
"pinned_symbol_libs": []
},
"meta": {
"filename": "encoder.kicad_pro",
"version": 3
},
"net_settings": {
"classes": [
{
"bus_width": 12,
"clearance": 0.2,
"diff_pair_gap": 0.25,
"diff_pair_via_gap": 0.25,
"diff_pair_width": 0.2,
"line_style": 0,
"microvia_diameter": 0.3,
"microvia_drill": 0.1,
"name": "Default",
"pcb_color": "rgba(0, 0, 0, 0.000)",
"priority": 2147483647,
"schematic_color": "rgba(0, 0, 0, 0.000)",
"track_width": 0.2,
"via_diameter": 0.8,
"via_drill": 0.4,
"wire_width": 6
}
],
"meta": {
"version": 4
},
"net_colors": null,
"netclass_assignments": null,
"netclass_patterns": []
},
"pcbnew": {
"last_paths": {
"gencad": "",
"idf": "",
"netlist": "",
"plot": "gerbers/",
"pos_files": "",
"specctra_dsn": "",
"step": "",
"svg": "",
"vrml": ""
},
"page_layout_descr_file": ""
},
"schematic": {
"annotate_start_num": 0,
"bom_export_filename": "BOM.csv",
"bom_fmt_presets": [],
"bom_fmt_settings": {
"field_delimiter": ",",
"keep_line_breaks": false,
"keep_tabs": false,
"name": "CSV",
"ref_delimiter": ",",
"ref_range_delimiter": "",
"string_delimiter": "\""
},
"bom_presets": [],
"bom_settings": {
"exclude_dnp": false,
"fields_ordered": [
{
"group_by": false,
"label": "Reference",
"name": "Reference",
"show": true
},
{
"group_by": true,
"label": "Value",
"name": "Value",
"show": true
},
{
"group_by": false,
"label": "Datasheet",
"name": "Datasheet",
"show": true
},
{
"group_by": false,
"label": "Footprint",
"name": "Footprint",
"show": true
},
{
"group_by": false,
"label": "Qty",
"name": "${QUANTITY}",
"show": true
},
{
"group_by": true,
"label": "DNP",
"name": "${DNP}",
"show": true
},
{
"group_by": false,
"label": "#",
"name": "${ITEM_NUMBER}",
"show": false
},
{
"group_by": false,
"label": "Manufacturer",
"name": "Manufacturer",
"show": false
},
{
"group_by": false,
"label": "Description",
"name": "Description",
"show": false
}
],
"filter_string": "",
"group_symbols": true,
"include_excluded_from_bom": false,
"name": "",
"sort_asc": true,
"sort_field": "Reference"
},
"connection_grid_size": 50.0,
"drawing": {
"dashed_lines_dash_length_ratio": 12.0,
"dashed_lines_gap_length_ratio": 3.0,
"default_line_thickness": 6.0,
"default_text_size": 50.0,
"field_names": [],
"intersheets_ref_own_page": false,
"intersheets_ref_prefix": "",
"intersheets_ref_short": false,
"intersheets_ref_show": false,
"intersheets_ref_suffix": "",
"junction_size_choice": 3,
"label_size_ratio": 0.375,
"operating_point_overlay_i_precision": 3,
"operating_point_overlay_i_range": "~A",
"operating_point_overlay_v_precision": 3,
"operating_point_overlay_v_range": "~V",
"overbar_offset_ratio": 1.23,
"pin_symbol_size": 25.0,
"text_offset_ratio": 0.15
},
"legacy_lib_dir": "",
"legacy_lib_list": [],
"meta": {
"version": 1
},
"net_format_name": "",
"ngspice": {
"fix_include_paths": true,
"meta": {
"version": 0
},
"model_mode": 4,
"workbook_filename": ""
},
"page_layout_descr_file": "",
"plot_directory": "",
"space_save_all_events": true,
"spice_current_sheet_as_root": false,
"spice_external_command": "spice \"%I\"",
"spice_model_current_sheet_as_root": true,
"spice_save_all_currents": false,
"spice_save_all_dissipations": false,
"spice_save_all_voltages": false,
"subpart_first_id": 65,
"subpart_id_separator": 0
},
"sheets": [
[
"8d999898-5824-4200-a5bb-e5cd72e34b91",
"Root"
],
[
"73c963f6-4efe-4c55-af10-7cb25f15b728",
"SSI_422_2"
],
[
"8303fa26-68ce-4671-900d-4c072b8eabbd",
"RS-232_1"
],
[
"80264a45-619f-4fbb-976c-6c15dcb432b8",
"SSI_422_1"
]
],
"text_variables": {}
}

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,4 @@
(fp_lib_table
(version 7)
(lib (name "my_footprints")(type "KiCad")(uri "${KIPRJMOD}/my_footprints.pretty")(options "")(descr ""))
)

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,169 @@
%TF.GenerationSoftware,KiCad,Pcbnew,9.0.0*%
%TF.CreationDate,2025-04-04T18:35:25+03:00*%
%TF.ProjectId,encoder,656e636f-6465-4722-9e6b-696361645f70,rev?*%
%TF.SameCoordinates,Original*%
%TF.FileFunction,Soldermask,Bot*%
%TF.FilePolarity,Negative*%
%FSLAX46Y46*%
G04 Gerber Fmt 4.6, Leading zero omitted, Abs format (unit mm)*
G04 Created by KiCad (PCBNEW 9.0.0) date 2025-04-04 18:35:25*
%MOMM*%
%LPD*%
G01*
G04 APERTURE LIST*
G04 Aperture macros list*
%AMRoundRect*
0 Rectangle with rounded corners*
0 $1 Rounding radius*
0 $2 $3 $4 $5 $6 $7 $8 $9 X,Y pos of 4 corners*
0 Add a 4 corners polygon primitive as box body*
4,1,4,$2,$3,$4,$5,$6,$7,$8,$9,$2,$3,0*
0 Add four circle primitives for the rounded corners*
1,1,$1+$1,$2,$3*
1,1,$1+$1,$4,$5*
1,1,$1+$1,$6,$7*
1,1,$1+$1,$8,$9*
0 Add four rect primitives between the rounded corners*
20,1,$1+$1,$2,$3,$4,$5,0*
20,1,$1+$1,$4,$5,$6,$7,0*
20,1,$1+$1,$6,$7,$8,$9,0*
20,1,$1+$1,$8,$9,$2,$3,0*%
G04 Aperture macros list end*
%ADD10C,3.000000*%
%ADD11C,3.200000*%
%ADD12R,1.000000X1.000000*%
%ADD13C,1.000000*%
%ADD14C,3.250000*%
%ADD15RoundRect,0.250000X-0.650000X-0.650000X0.650000X-0.650000X0.650000X0.650000X-0.650000X0.650000X0*%
%ADD16C,1.800000*%
%ADD17C,1.500000*%
%ADD18RoundRect,0.381000X0.619000X0.381000X-0.619000X0.381000X-0.619000X-0.381000X0.619000X-0.381000X0*%
%ADD19RoundRect,0.381000X0.762000X0.381000X-0.762000X0.381000X-0.762000X-0.381000X0.762000X-0.381000X0*%
%ADD20C,4.000000*%
%ADD21R,1.600000X1.600000*%
%ADD22C,1.600000*%
%ADD23RoundRect,0.250000X-1.050000X1.050000X-1.050000X-1.050000X1.050000X-1.050000X1.050000X1.050000X0*%
%ADD24C,2.600000*%
%ADD25R,1.700000X1.700000*%
%ADD26C,1.700000*%
%ADD27C,3.500000*%
G04 APERTURE END LIST*
D10*
%TO.C,TP2*%
X129500000Y-111000000D03*
%TD*%
D11*
%TO.C,J11*%
X74500000Y-126500000D03*
%TD*%
%TO.C,J5*%
X74500000Y-53500000D03*
%TD*%
D10*
%TO.C,TP1*%
X129500000Y-106000000D03*
%TD*%
D11*
%TO.C,J7*%
X144500000Y-126500000D03*
%TD*%
D10*
%TO.C,TP3*%
X144000000Y-90000000D03*
%TD*%
D11*
%TO.C,J6*%
X144500000Y-53500000D03*
%TD*%
D12*
%TO.C,J3*%
X145246400Y-77435400D03*
D13*
X145246400Y-78705400D03*
X145246400Y-79975400D03*
X145246400Y-81245400D03*
X145246400Y-82515400D03*
X145246400Y-83785400D03*
%TD*%
D14*
%TO.C,J9*%
X117673600Y-53459000D03*
X125173600Y-53459000D03*
D15*
X119583600Y-59809000D03*
D16*
X120853600Y-62349000D03*
X122123600Y-59809000D03*
X123393600Y-62349000D03*
%TD*%
D17*
%TO.C,Y1*%
X111157400Y-97780000D03*
X111157400Y-102660000D03*
%TD*%
D18*
%TO.C,Q3*%
X100750800Y-82000000D03*
X98210800Y-82000000D03*
D19*
X93130800Y-82000000D03*
X88050800Y-82000000D03*
%TD*%
D18*
%TO.C,Q2*%
X100679200Y-115058400D03*
X98139200Y-115058400D03*
D19*
X93059200Y-115058400D03*
X87979200Y-115058400D03*
%TD*%
D20*
%TO.C,J8*%
X78870900Y-119604300D03*
X78870900Y-94604300D03*
D21*
X79170900Y-101564300D03*
D22*
X79170900Y-104334300D03*
X79170900Y-107104300D03*
X79170900Y-109874300D03*
X79170900Y-112644300D03*
X76330900Y-102949300D03*
X76330900Y-105719300D03*
X76330900Y-108489300D03*
X76330900Y-111259300D03*
%TD*%
D23*
%TO.C,J1*%
X143357600Y-114500000D03*
D24*
X143357600Y-119500000D03*
%TD*%
D20*
%TO.C,J10*%
X78942500Y-86545900D03*
X78942500Y-61545900D03*
D21*
X79242500Y-68505900D03*
D22*
X79242500Y-71275900D03*
X79242500Y-74045900D03*
X79242500Y-76815900D03*
X79242500Y-79585900D03*
X76402500Y-69890900D03*
X76402500Y-72660900D03*
X76402500Y-75430900D03*
X76402500Y-78200900D03*
%TD*%
D25*
%TO.C,J2*%
X140544800Y-102108000D03*
D26*
X140544800Y-99608000D03*
X142544800Y-99608000D03*
X142544800Y-102108000D03*
D27*
X145254800Y-94838000D03*
X145254800Y-106878000D03*
%TD*%
M02*

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,51 @@
%TF.GenerationSoftware,KiCad,Pcbnew,9.0.0*%
%TF.CreationDate,2025-04-04T18:35:26+03:00*%
%TF.ProjectId,encoder,656e636f-6465-4722-9e6b-696361645f70,rev?*%
%TF.SameCoordinates,Original*%
%TF.FileFunction,Profile,NP*%
%FSLAX46Y46*%
G04 Gerber Fmt 4.6, Leading zero omitted, Abs format (unit mm)*
G04 Created by KiCad (PCBNEW 9.0.0) date 2025-04-04 18:35:26*
%MOMM*%
%LPD*%
G01*
G04 APERTURE LIST*
%TA.AperFunction,Profile*%
%ADD10C,0.050000*%
%TD*%
G04 APERTURE END LIST*
D10*
X96000000Y-89500000D02*
X96000000Y-62500000D01*
X95500000Y-62500000D02*
G75*
G02*
X96000000Y-62500000I250000J0D01*
G01*
X96000000Y-89500000D02*
G75*
G02*
X95500000Y-89500000I-250000J0D01*
G01*
X95500000Y-62500000D02*
X95500000Y-89500000D01*
X95500000Y-95500000D02*
G75*
G02*
X96000000Y-95500000I250000J0D01*
G01*
X96000000Y-122500000D02*
G75*
G02*
X95500000Y-122500000I-250000J0D01*
G01*
X95500000Y-95500000D02*
X95500000Y-122500000D01*
X96000000Y-122500000D02*
X96000000Y-95500000D01*
X70500000Y-49500000D02*
X148500000Y-49500000D01*
X148500000Y-130500000D01*
X70500000Y-130500000D01*
X70500000Y-49500000D01*
M02*

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,544 @@
%TF.GenerationSoftware,KiCad,Pcbnew,9.0.0*%
%TF.CreationDate,2025-04-04T18:35:25+03:00*%
%TF.ProjectId,encoder,656e636f-6465-4722-9e6b-696361645f70,rev?*%
%TF.SameCoordinates,Original*%
%TF.FileFunction,Soldermask,Top*%
%TF.FilePolarity,Negative*%
%FSLAX46Y46*%
G04 Gerber Fmt 4.6, Leading zero omitted, Abs format (unit mm)*
G04 Created by KiCad (PCBNEW 9.0.0) date 2025-04-04 18:35:25*
%MOMM*%
%LPD*%
G01*
G04 APERTURE LIST*
G04 Aperture macros list*
%AMRoundRect*
0 Rectangle with rounded corners*
0 $1 Rounding radius*
0 $2 $3 $4 $5 $6 $7 $8 $9 X,Y pos of 4 corners*
0 Add a 4 corners polygon primitive as box body*
4,1,4,$2,$3,$4,$5,$6,$7,$8,$9,$2,$3,0*
0 Add four circle primitives for the rounded corners*
1,1,$1+$1,$2,$3*
1,1,$1+$1,$4,$5*
1,1,$1+$1,$6,$7*
1,1,$1+$1,$8,$9*
0 Add four rect primitives between the rounded corners*
20,1,$1+$1,$2,$3,$4,$5,0*
20,1,$1+$1,$4,$5,$6,$7,0*
20,1,$1+$1,$6,$7,$8,$9,0*
20,1,$1+$1,$8,$9,$2,$3,0*%
%AMOutline4P*
0 Free polygon, 4 corners , with rotation*
0 The origin of the aperture is its center*
0 number of corners: always 4*
0 $1 to $8 corner X, Y*
0 $9 Rotation angle, in degrees counterclockwise*
0 create outline with 4 corners*
4,1,4,$1,$2,$3,$4,$5,$6,$7,$8,$1,$2,$9*%
G04 Aperture macros list end*
%ADD10RoundRect,0.237500X0.237500X-0.300000X0.237500X0.300000X-0.237500X0.300000X-0.237500X-0.300000X0*%
%ADD11RoundRect,0.237500X-0.300000X-0.237500X0.300000X-0.237500X0.300000X0.237500X-0.300000X0.237500X0*%
%ADD12C,3.000000*%
%ADD13RoundRect,0.250000X-0.337500X-0.475000X0.337500X-0.475000X0.337500X0.475000X-0.337500X0.475000X0*%
%ADD14RoundRect,0.150000X0.587500X0.150000X-0.587500X0.150000X-0.587500X-0.150000X0.587500X-0.150000X0*%
%ADD15C,3.200000*%
%ADD16RoundRect,0.237500X0.300000X0.237500X-0.300000X0.237500X-0.300000X-0.237500X0.300000X-0.237500X0*%
%ADD17RoundRect,0.375000X-0.625000X-0.375000X0.625000X-0.375000X0.625000X0.375000X-0.625000X0.375000X0*%
%ADD18RoundRect,0.500000X-0.500000X-1.400000X0.500000X-1.400000X0.500000X1.400000X-0.500000X1.400000X0*%
%ADD19RoundRect,0.237500X0.250000X0.237500X-0.250000X0.237500X-0.250000X-0.237500X0.250000X-0.237500X0*%
%ADD20Outline4P,-1.800000X-1.150000X1.800000X-0.550000X1.800000X0.550000X-1.800000X1.150000X90.000000*%
%ADD21Outline4P,-1.800000X-1.150000X1.800000X-0.550000X1.800000X0.550000X-1.800000X1.150000X270.000000*%
%ADD22RoundRect,0.250000X0.475000X-0.337500X0.475000X0.337500X-0.475000X0.337500X-0.475000X-0.337500X0*%
%ADD23RoundRect,0.150000X-0.512500X-0.150000X0.512500X-0.150000X0.512500X0.150000X-0.512500X0.150000X0*%
%ADD24RoundRect,0.250000X0.625000X-0.375000X0.625000X0.375000X-0.625000X0.375000X-0.625000X-0.375000X0*%
%ADD25RoundRect,0.237500X0.237500X-0.250000X0.237500X0.250000X-0.237500X0.250000X-0.237500X-0.250000X0*%
%ADD26RoundRect,0.250000X0.650000X-1.000000X0.650000X1.000000X-0.650000X1.000000X-0.650000X-1.000000X0*%
%ADD27RoundRect,0.150000X0.875000X0.150000X-0.875000X0.150000X-0.875000X-0.150000X0.875000X-0.150000X0*%
%ADD28RoundRect,0.075000X-0.662500X-0.075000X0.662500X-0.075000X0.662500X0.075000X-0.662500X0.075000X0*%
%ADD29RoundRect,0.075000X-0.075000X-0.662500X0.075000X-0.662500X0.075000X0.662500X-0.075000X0.662500X0*%
%ADD30Outline4P,-1.800000X-1.150000X1.800000X-0.550000X1.800000X0.550000X-1.800000X1.150000X0.000000*%
%ADD31Outline4P,-1.800000X-1.150000X1.800000X-0.550000X1.800000X0.550000X-1.800000X1.150000X180.000000*%
%ADD32RoundRect,0.150000X-0.150000X0.825000X-0.150000X-0.825000X0.150000X-0.825000X0.150000X0.825000X0*%
%ADD33R,1.000000X1.000000*%
%ADD34C,1.000000*%
%ADD35RoundRect,0.112500X-0.112500X-0.637500X0.112500X-0.637500X0.112500X0.637500X-0.112500X0.637500X0*%
%ADD36RoundRect,0.250000X-0.475000X0.337500X-0.475000X-0.337500X0.475000X-0.337500X0.475000X0.337500X0*%
%ADD37RoundRect,0.237500X-0.237500X0.300000X-0.237500X-0.300000X0.237500X-0.300000X0.237500X0.300000X0*%
%ADD38RoundRect,0.250000X-0.650000X1.000000X-0.650000X-1.000000X0.650000X-1.000000X0.650000X1.000000X0*%
%ADD39RoundRect,0.237500X-0.237500X0.250000X-0.237500X-0.250000X0.237500X-0.250000X0.237500X0.250000X0*%
%ADD40C,3.250000*%
%ADD41RoundRect,0.250000X-0.650000X-0.650000X0.650000X-0.650000X0.650000X0.650000X-0.650000X0.650000X0*%
%ADD42C,1.800000*%
%ADD43C,1.500000*%
%ADD44RoundRect,0.381000X0.619000X0.381000X-0.619000X0.381000X-0.619000X-0.381000X0.619000X-0.381000X0*%
%ADD45RoundRect,0.381000X0.762000X0.381000X-0.762000X0.381000X-0.762000X-0.381000X0.762000X-0.381000X0*%
%ADD46C,4.000000*%
%ADD47R,1.600000X1.600000*%
%ADD48C,1.600000*%
%ADD49RoundRect,0.250000X-1.050000X1.050000X-1.050000X-1.050000X1.050000X-1.050000X1.050000X1.050000X0*%
%ADD50C,2.600000*%
%ADD51R,1.700000X1.700000*%
%ADD52C,1.700000*%
%ADD53C,3.500000*%
G04 APERTURE END LIST*
D10*
%TO.C,C8*%
X126593600Y-94435000D03*
X126593600Y-92710000D03*
%TD*%
D11*
%TO.C,C11*%
X98596400Y-108556000D03*
X100321400Y-108556000D03*
%TD*%
D12*
%TO.C,TP2*%
X129500000Y-111000000D03*
%TD*%
D13*
%TO.C,C23*%
X89481000Y-79409200D03*
X91556000Y-79409200D03*
%TD*%
D14*
%TO.C,D9*%
X83485100Y-70359100D03*
X83485100Y-68459100D03*
X81610100Y-69409100D03*
%TD*%
D15*
%TO.C,J11*%
X74500000Y-126500000D03*
%TD*%
D16*
%TO.C,C5*%
X111200100Y-100736400D03*
X109475100Y-100736400D03*
%TD*%
D17*
%TO.C,U1*%
X133959600Y-88110000D03*
X133959600Y-90410000D03*
D18*
X140259600Y-90410000D03*
D17*
X133959600Y-92710000D03*
%TD*%
D15*
%TO.C,J5*%
X74500000Y-53500000D03*
%TD*%
D19*
%TO.C,R3*%
X146151600Y-87071200D03*
X144326600Y-87071200D03*
%TD*%
D10*
%TO.C,C2*%
X131572800Y-89849000D03*
X131572800Y-88124000D03*
%TD*%
D20*
%TO.C,D7*%
X109169600Y-65553800D03*
D21*
X109169600Y-59753800D03*
%TD*%
D22*
%TO.C,C17*%
X117847600Y-68583200D03*
X117847600Y-66508200D03*
%TD*%
D12*
%TO.C,TP1*%
X129500000Y-106000000D03*
%TD*%
D23*
%TO.C,U2*%
X130911600Y-98567200D03*
X130911600Y-99517200D03*
X130911600Y-100467200D03*
X133186600Y-100467200D03*
X133186600Y-99517200D03*
X133186600Y-98567200D03*
%TD*%
D24*
%TO.C,F1*%
X100679200Y-120138400D03*
X100679200Y-117338400D03*
%TD*%
%TO.C,F2*%
X100750800Y-87080000D03*
X100750800Y-84280000D03*
%TD*%
D11*
%TO.C,C4*%
X111152600Y-95961200D03*
X112877600Y-95961200D03*
%TD*%
D16*
%TO.C,C15*%
X121556000Y-66398800D03*
X119831000Y-66398800D03*
%TD*%
D25*
%TO.C,R6*%
X120853200Y-93163400D03*
X120853200Y-91338400D03*
%TD*%
D11*
%TO.C,C9*%
X121311500Y-107492800D03*
X123036500Y-107492800D03*
%TD*%
D26*
%TO.C,D5*%
X126848000Y-73728200D03*
X126848000Y-69728200D03*
%TD*%
D27*
%TO.C,U6*%
X100371600Y-73211600D03*
X100371600Y-71941600D03*
X100371600Y-70671600D03*
X100371600Y-69401600D03*
X100371600Y-68131600D03*
X100371600Y-66861600D03*
X100371600Y-65591600D03*
X100371600Y-64321600D03*
X91071600Y-64321600D03*
X91071600Y-65591600D03*
X91071600Y-66861600D03*
X91071600Y-68131600D03*
X91071600Y-69401600D03*
X91071600Y-70671600D03*
X91071600Y-71941600D03*
X91071600Y-73211600D03*
%TD*%
D15*
%TO.C,J7*%
X144500000Y-126500000D03*
%TD*%
D11*
%TO.C,C7*%
X112878700Y-93878400D03*
X114603700Y-93878400D03*
%TD*%
%TO.C,C1*%
X133911000Y-111201200D03*
X135636000Y-111201200D03*
%TD*%
D12*
%TO.C,TP3*%
X144000000Y-90000000D03*
%TD*%
D13*
%TO.C,C14*%
X89409400Y-112467600D03*
X91484400Y-112467600D03*
%TD*%
D28*
%TO.C,U3*%
X116128800Y-97783200D03*
X116128800Y-98283200D03*
X116128800Y-98783200D03*
X116128800Y-99283200D03*
X116128800Y-99783200D03*
X116128800Y-100283200D03*
X116128800Y-100783200D03*
X116128800Y-101283200D03*
X116128800Y-101783200D03*
X116128800Y-102283200D03*
X116128800Y-102783200D03*
X116128800Y-103283200D03*
D29*
X117541300Y-104695700D03*
X118041300Y-104695700D03*
X118541300Y-104695700D03*
X119041300Y-104695700D03*
X119541300Y-104695700D03*
X120041300Y-104695700D03*
X120541300Y-104695700D03*
X121041300Y-104695700D03*
X121541300Y-104695700D03*
X122041300Y-104695700D03*
X122541300Y-104695700D03*
X123041300Y-104695700D03*
D28*
X124453800Y-103283200D03*
X124453800Y-102783200D03*
X124453800Y-102283200D03*
X124453800Y-101783200D03*
X124453800Y-101283200D03*
X124453800Y-100783200D03*
X124453800Y-100283200D03*
X124453800Y-99783200D03*
X124453800Y-99283200D03*
X124453800Y-98783200D03*
X124453800Y-98283200D03*
X124453800Y-97783200D03*
D29*
X123041300Y-96370700D03*
X122541300Y-96370700D03*
X122041300Y-96370700D03*
X121541300Y-96370700D03*
X121041300Y-96370700D03*
X120541300Y-96370700D03*
X120041300Y-96370700D03*
X119541300Y-96370700D03*
X119041300Y-96370700D03*
X118541300Y-96370700D03*
X118041300Y-96370700D03*
X117541300Y-96370700D03*
%TD*%
D15*
%TO.C,J6*%
X144500000Y-53500000D03*
%TD*%
D30*
%TO.C,D1*%
X133950800Y-105968800D03*
D31*
X139750800Y-105968800D03*
%TD*%
D27*
%TO.C,U4*%
X100300000Y-106270000D03*
X100300000Y-105000000D03*
X100300000Y-103730000D03*
X100300000Y-102460000D03*
X100300000Y-101190000D03*
X100300000Y-99920000D03*
X100300000Y-98650000D03*
X100300000Y-97380000D03*
X91000000Y-97380000D03*
X91000000Y-98650000D03*
X91000000Y-99920000D03*
X91000000Y-101190000D03*
X91000000Y-102460000D03*
X91000000Y-103730000D03*
X91000000Y-105000000D03*
X91000000Y-106270000D03*
%TD*%
D32*
%TO.C,U5*%
X121810000Y-71050000D03*
X120540000Y-71050000D03*
X119270000Y-71050000D03*
X118000000Y-71050000D03*
X116730000Y-71050000D03*
X115460000Y-71050000D03*
X114190000Y-71050000D03*
X112920000Y-71050000D03*
X112920000Y-76000000D03*
X114190000Y-76000000D03*
X115460000Y-76000000D03*
X116730000Y-76000000D03*
X118000000Y-76000000D03*
X119270000Y-76000000D03*
X120540000Y-76000000D03*
X121810000Y-76000000D03*
%TD*%
D13*
%TO.C,C18*%
X120540000Y-68481600D03*
X122615000Y-68481600D03*
%TD*%
D33*
%TO.C,J3*%
X145246400Y-77435400D03*
D34*
X145246400Y-78705400D03*
X145246400Y-79975400D03*
X145246400Y-81245400D03*
X145246400Y-82515400D03*
X145246400Y-83785400D03*
%TD*%
D19*
%TO.C,R1*%
X137308600Y-98552000D03*
X135483600Y-98552000D03*
%TD*%
D16*
%TO.C,C10*%
X118159700Y-93878400D03*
X116434700Y-93878400D03*
%TD*%
D13*
%TO.C,C3*%
X126644400Y-88138000D03*
X128719400Y-88138000D03*
%TD*%
D30*
%TO.C,D2*%
X133595200Y-119481600D03*
D31*
X139395200Y-119481600D03*
%TD*%
D35*
%TO.C,Q1*%
X127670800Y-100898000D03*
X128970800Y-100898000D03*
X128320800Y-98238000D03*
%TD*%
D36*
%TO.C,C19*%
X115460000Y-66508200D03*
X115460000Y-68583200D03*
%TD*%
D16*
%TO.C,C21*%
X92775200Y-75446800D03*
X91050200Y-75446800D03*
%TD*%
D37*
%TO.C,C6*%
X113741200Y-102997000D03*
X113741200Y-104722000D03*
%TD*%
D14*
%TO.C,D8*%
X83434300Y-74016700D03*
X83434300Y-72116700D03*
X81559300Y-73066700D03*
%TD*%
D13*
%TO.C,C13*%
X98401000Y-112467600D03*
X100476000Y-112467600D03*
%TD*%
D14*
%TO.C,D4*%
X83413500Y-103417500D03*
X83413500Y-101517500D03*
X81538500Y-102467500D03*
%TD*%
D19*
%TO.C,R2*%
X137310500Y-100482400D03*
X135485500Y-100482400D03*
%TD*%
D13*
%TO.C,C22*%
X98472600Y-79409200D03*
X100547600Y-79409200D03*
%TD*%
D14*
%TO.C,D3*%
X83362700Y-107075100D03*
X83362700Y-105175100D03*
X81487700Y-106125100D03*
%TD*%
D38*
%TO.C,D6*%
X126898800Y-62399800D03*
X126898800Y-66399800D03*
%TD*%
D11*
%TO.C,C20*%
X98668000Y-75497600D03*
X100393000Y-75497600D03*
%TD*%
D16*
%TO.C,C16*%
X122064000Y-78336800D03*
X120339000Y-78336800D03*
%TD*%
D39*
%TO.C,R4*%
X130911600Y-94999800D03*
X130911600Y-96824800D03*
%TD*%
D16*
%TO.C,C12*%
X92703600Y-108505200D03*
X90978600Y-108505200D03*
%TD*%
D19*
%TO.C,R5*%
X112014000Y-104749600D03*
X110189000Y-104749600D03*
%TD*%
D40*
%TO.C,J9*%
X117673600Y-53459000D03*
X125173600Y-53459000D03*
D41*
X119583600Y-59809000D03*
D42*
X120853600Y-62349000D03*
X122123600Y-59809000D03*
X123393600Y-62349000D03*
%TD*%
D43*
%TO.C,Y1*%
X111157400Y-97780000D03*
X111157400Y-102660000D03*
%TD*%
D44*
%TO.C,Q3*%
X100750800Y-82000000D03*
X98210800Y-82000000D03*
D45*
X93130800Y-82000000D03*
X88050800Y-82000000D03*
%TD*%
D44*
%TO.C,Q2*%
X100679200Y-115058400D03*
X98139200Y-115058400D03*
D45*
X93059200Y-115058400D03*
X87979200Y-115058400D03*
%TD*%
D46*
%TO.C,J8*%
X78870900Y-119604300D03*
X78870900Y-94604300D03*
D47*
X79170900Y-101564300D03*
D48*
X79170900Y-104334300D03*
X79170900Y-107104300D03*
X79170900Y-109874300D03*
X79170900Y-112644300D03*
X76330900Y-102949300D03*
X76330900Y-105719300D03*
X76330900Y-108489300D03*
X76330900Y-111259300D03*
%TD*%
D49*
%TO.C,J1*%
X143357600Y-114500000D03*
D50*
X143357600Y-119500000D03*
%TD*%
D46*
%TO.C,J10*%
X78942500Y-86545900D03*
X78942500Y-61545900D03*
D47*
X79242500Y-68505900D03*
D48*
X79242500Y-71275900D03*
X79242500Y-74045900D03*
X79242500Y-76815900D03*
X79242500Y-79585900D03*
X76402500Y-69890900D03*
X76402500Y-72660900D03*
X76402500Y-75430900D03*
X76402500Y-78200900D03*
%TD*%
D51*
%TO.C,J2*%
X140544800Y-102108000D03*
D52*
X140544800Y-99608000D03*
X142544800Y-99608000D03*
X142544800Y-102108000D03*
D53*
X145254800Y-94838000D03*
X145254800Y-106878000D03*
%TD*%
M02*

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,35 @@
Drill report for encoder.kicad_pcb
Created on 2025-04-04T18:35:21+0300
Copper Layer Stackup:
=============================================================
L1 : F.Cu front
L2 : B.Cu back
Drill file 'encoder.drl' contains
plated through holes:
=============================================================
T1 0.400mm 0.0157" (52 holes)
T2 0.600mm 0.0236" (5 holes)
T3 0.600mm 0.0236" (8 holes)
T4 0.700mm 0.0276" (6 holes)
T5 0.800mm 0.0315" (2 holes)
T6 0.900mm 0.0354" (4 holes)
T7 0.920mm 0.0362" (4 holes)
T8 1.000mm 0.0394" (18 holes)
T9 1.300mm 0.0512" (2 holes)
T10 1.500mm 0.0591" (3 holes)
T11 2.330mm 0.0917" (2 holes)
T12 3.200mm 0.1260" (4 holes)
Total plated holes count 110
Not plated through holes are merged with plated holes
unplated through holes:
=============================================================
T13 3.200mm 0.1260" (5 holes)
T14 3.250mm 0.1280" (1 hole)
Total unplated holes count 6

View File

@ -0,0 +1,109 @@
{
"Header": {
"GenerationSoftware": {
"Vendor": "KiCad",
"Application": "Pcbnew",
"Version": "9.0.0"
},
"CreationDate": "2025-04-04T18:35:26+03:00"
},
"GeneralSpecs": {
"ProjectId": {
"Name": "encoder",
"GUID": "656e636f-6465-4722-9e6b-696361645f70",
"Revision": "rev?"
},
"Size": {
"X": 78.05,
"Y": 81.05
},
"LayerNumber": 2,
"BoardThickness": 1.6,
"Finish": "HAL SnPb"
},
"DesignRules": [
{
"Layers": "Outer",
"PadToPad": 0.2,
"PadToTrack": 0.2,
"TrackToTrack": 0.2,
"MinLineWidth": 0.2,
"TrackToRegion": 0.2,
"RegionToRegion": 0.2
}
],
"FilesAttributes": [
{
"Path": "encoder-F_Cu.gbr",
"FileFunction": "Copper,L1,Top",
"FilePolarity": "Positive"
},
{
"Path": "encoder-B_Cu.gbr",
"FileFunction": "Copper,L2,Bot",
"FilePolarity": "Positive"
},
{
"Path": "encoder-F_Silkscreen.gbr",
"FileFunction": "Legend,Top",
"FilePolarity": "Positive"
},
{
"Path": "encoder-B_Silkscreen.gbr",
"FileFunction": "Legend,Bot",
"FilePolarity": "Positive"
},
{
"Path": "encoder-F_Mask.gbr",
"FileFunction": "SolderMask,Top",
"FilePolarity": "Negative"
},
{
"Path": "encoder-B_Mask.gbr",
"FileFunction": "SolderMask,Bot",
"FilePolarity": "Negative"
},
{
"Path": "encoder-Edge_Cuts.gbr",
"FileFunction": "Profile",
"FilePolarity": "Positive"
}
],
"MaterialStackup": [
{
"Type": "Legend",
"Name": "Top Silk Screen"
},
{
"Type": "SolderMask",
"Thickness": 0.01,
"Name": "Top Solder Mask"
},
{
"Type": "Copper",
"Thickness": 0.035,
"Name": "F.Cu"
},
{
"Type": "Dielectric",
"Thickness": 1.51,
"Material": "FR4",
"Name": "F.Cu/B.Cu",
"Notes": "Type: dielectric layer 1 (from F.Cu to B.Cu)"
},
{
"Type": "Copper",
"Thickness": 0.035,
"Name": "B.Cu"
},
{
"Type": "SolderMask",
"Thickness": 0.01,
"Name": "Bottom Solder Mask"
},
{
"Type": "Legend",
"Name": "Bottom Silk Screen"
}
]
}

View File

@ -0,0 +1,170 @@
M48
; DRILL file {KiCad 9.0.0} date 2025-04-04T18:35:22+0300
; FORMAT={-:-/ absolute / metric / decimal}
; #@! TF.CreationDate,2025-04-04T18:35:22+03:00
; #@! TF.GenerationSoftware,Kicad,Pcbnew,9.0.0
; #@! TF.FileFunction,MixedPlating,1,2
FMAT,2
METRIC
; #@! TA.AperFunction,Plated,PTH,ViaDrill
T1C0.400
; #@! TA.AperFunction,Plated,PTH,ViaDrill
T2C0.600
; #@! TA.AperFunction,Plated,PTH,ComponentDrill
T3C0.600
; #@! TA.AperFunction,Plated,PTH,ComponentDrill
T4C0.700
; #@! TA.AperFunction,Plated,PTH,ComponentDrill
T5C0.800
; #@! TA.AperFunction,Plated,PTH,ComponentDrill
T6C0.900
; #@! TA.AperFunction,Plated,PTH,ComponentDrill
T7C0.920
; #@! TA.AperFunction,Plated,PTH,ComponentDrill
T8C1.000
; #@! TA.AperFunction,Plated,PTH,ComponentDrill
T9C1.300
; #@! TA.AperFunction,Plated,PTH,ComponentDrill
T10C1.500
; #@! TA.AperFunction,Plated,PTH,ComponentDrill
T11C2.330
; #@! TA.AperFunction,Plated,PTH,ComponentDrill
T12C3.200
; #@! TA.AperFunction,NonPlated,NPTH,ComponentDrill
T13C3.200
; #@! TA.AperFunction,NonPlated,NPTH,ComponentDrill
T14C3.250
%
G90
G05
T1
X81.488Y-106.125
X81.559Y-73.067
X83.363Y-105.175
X83.413Y-101.517
X83.434Y-72.117
X83.485Y-68.459
X103.124Y-98.65
X103.175Y-86.055
X103.175Y-87.921
X103.378Y-111.354
X103.429Y-113.284
X105.308Y-111.354
X105.308Y-113.233
X106.832Y-82.855
X106.832Y-86.106
X108.102Y-69.139
X109.068Y-102.311
X110.236Y-69.139
X112.014Y-104.75
X112.37Y-69.088
X113.741Y-102.997
X114.097Y-77.927
X114.605Y-60.909
X114.656Y-58.674
X116.535Y-105.816
X117.683Y-106.72
X118.0Y-76.0
X118.516Y-78.384
X118.711Y-107.745
X119.27Y-76.0
X120.54Y-76.098
X121.183Y-100.863
X121.31Y-72.796
X122.123Y-94.234
X122.834Y-70.968
X122.834Y-73.812
X123.038Y-90.373
X126.441Y-103.008
X126.594Y-94.435
X126.848Y-69.728
X126.899Y-62.4
X127.508Y-96.114
X128.067Y-102.972
X128.981Y-100.889
X132.893Y-96.723
X132.893Y-109.372
X132.944Y-103.175
X134.874Y-96.723
X134.874Y-109.372
X134.925Y-103.175
X139.5Y-104.0
X143.358Y-84.938
T2
X100.679Y-120.138
X100.751Y-87.08
X109.17Y-65.554
X133.909Y-105.969
X133.96Y-92.71
T3
X87.979Y-115.058
X88.051Y-82.0
X93.059Y-115.058
X93.131Y-82.0
X98.139Y-115.058
X98.211Y-82.0
X100.679Y-115.058
X100.751Y-82.0
T4
X145.246Y-77.435
X145.246Y-78.705
X145.246Y-79.975
X145.246Y-81.245
X145.246Y-82.515
X145.246Y-83.785
T5
X111.157Y-97.78
X111.157Y-102.66
T6
X119.584Y-59.809
X120.854Y-62.349
X122.124Y-59.809
X123.394Y-62.349
T7
X140.545Y-99.608
X140.545Y-102.108
X142.545Y-99.608
X142.545Y-102.108
T8
X76.331Y-102.949
X76.331Y-105.719
X76.331Y-108.489
X76.331Y-111.259
X76.403Y-69.891
X76.403Y-72.661
X76.403Y-75.431
X76.403Y-78.201
X79.171Y-101.564
X79.171Y-104.334
X79.171Y-107.104
X79.171Y-109.874
X79.171Y-112.644
X79.242Y-68.506
X79.242Y-71.276
X79.242Y-74.046
X79.242Y-76.816
X79.242Y-79.586
T9
X143.358Y-114.5
X143.358Y-119.5
T10
X129.5Y-106.0
X129.5Y-111.0
X144.0Y-90.0
T11
X145.255Y-94.838
X145.255Y-106.878
T12
X78.871Y-94.604
X78.871Y-119.604
X78.942Y-61.546
X78.942Y-86.546
T13
X74.5Y-53.5
X74.5Y-126.5
X117.674Y-53.459
X144.5Y-53.5
X144.5Y-126.5
T14
X125.174Y-53.459
M30

View File

@ -0,0 +1,110 @@
(kicad_symbol_lib (version 20211014) (generator kicad_symbol_editor)
(symbol "ISO3086" (in_bom yes) (on_board yes)
(property "Reference" "U" (id 0) (at 0 20.32 0)
(effects (font (size 1.27 1.27)))
)
(property "Value" "ISO3086" (id 1) (at 0 17.78 0)
(effects (font (size 1.27 1.27)))
)
(property "Footprint" "Package_SO:SOIC-16W_7.5x10.3mm_P1.27mm" (id 2) (at 0 0 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "Datasheet" "" (id 3) (at 0 0 0)
(effects (font (size 1.27 1.27)) hide)
)
(property "ki_description" "RS422 isolator" (id 4) (at 0 0 0)
(effects (font (size 1.27 1.27)) hide)
)
(symbol "ISO3086_0_0"
(rectangle (start -11.43 15.24) (end 13.97 -15.24)
(stroke (width 0.254) (type default) (color 0 0 0 0))
(fill (type background))
)
(polyline
(pts
(xy -1.27 15.24)
(xy -1.27 -15.24)
)
(stroke (width 0) (type default) (color 0 0 0 0))
(fill (type none))
)
(polyline
(pts
(xy 1.27 15.24)
(xy 1.27 -15.24)
)
(stroke (width 0) (type default) (color 0 0 0 0))
(fill (type none))
)
(text "GALVANIC ISOLATION" (at 0 0.508 900)
(effects (font (size 1.016 1.016)))
)
)
(symbol "ISO3086_1_1"
(pin power_in line (at -6.35 17.78 270) (length 2.54)
(name "Vcc1" (effects (font (size 1.27 1.27))))
(number "1" (effects (font (size 1.27 1.27))))
)
(pin power_in line (at 8.89 -17.78 90) (length 2.54)
(name "GND2" (effects (font (size 1.27 1.27))))
(number "10" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at 16.51 -8.89 180) (length 2.54)
(name "Y" (effects (font (size 1.27 1.27))))
(number "11" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at 16.51 -5.08 180) (length 2.54)
(name "Z" (effects (font (size 1.27 1.27))))
(number "12" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at 16.51 5.08 180) (length 2.54)
(name "B" (effects (font (size 1.27 1.27))))
(number "13" (effects (font (size 1.27 1.27))))
)
(pin bidirectional line (at 16.51 8.89 180) (length 2.54)
(name "A" (effects (font (size 1.27 1.27))))
(number "14" (effects (font (size 1.27 1.27))))
)
(pin power_in line (at 11.43 -17.78 90) (length 2.54)
(name "GND2" (effects (font (size 1.27 1.27))))
(number "15" (effects (font (size 1.27 1.27))))
)
(pin power_in line (at 8.89 17.78 270) (length 2.54)
(name "Vcc2" (effects (font (size 1.27 1.27))))
(number "16" (effects (font (size 1.27 1.27))))
)
(pin power_in line (at -8.89 -17.78 90) (length 2.54)
(name "GND1" (effects (font (size 1.27 1.27))))
(number "2" (effects (font (size 1.27 1.27))))
)
(pin output line (at -13.97 -2.54 0) (length 2.54)
(name "R" (effects (font (size 1.27 1.27))))
(number "3" (effects (font (size 1.27 1.27))))
)
(pin input line (at -13.97 -5.08 0) (length 2.54)
(name "~{RE}" (effects (font (size 1.27 1.27))))
(number "4" (effects (font (size 1.27 1.27))))
)
(pin input line (at -13.97 7.62 0) (length 2.54)
(name "DE" (effects (font (size 1.27 1.27))))
(number "5" (effects (font (size 1.27 1.27))))
)
(pin input line (at -13.97 2.54 0) (length 2.54)
(name "D" (effects (font (size 1.27 1.27))))
(number "6" (effects (font (size 1.27 1.27))))
)
(pin power_in line (at -6.35 -17.78 90) (length 2.54)
(name "GND1" (effects (font (size 1.27 1.27))))
(number "7" (effects (font (size 1.27 1.27))))
)
(pin power_in line (at -3.81 -17.78 90) (length 2.54)
(name "GND1" (effects (font (size 1.27 1.27))))
(number "8" (effects (font (size 1.27 1.27))))
)
(pin power_in line (at 6.35 -17.78 90) (length 2.54)
(name "GND2" (effects (font (size 1.27 1.27))))
(number "9" (effects (font (size 1.27 1.27))))
)
)
)
)

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,19 @@
(footprint "B0505S-2W" (version 20211014) (generator pcbnew)
(layer "F.Cu")
(tedit 0)
(attr smd)
(fp_text reference "REF**" (at 10.2 7.2 unlocked) (layer "F.SilkS")
(effects (font (size 1 1) (thickness 0.15)))
(tstamp 063944c1-1524-42ff-905d-c6b885fc84e4)
)
(fp_text value "B0505S-2W" (at 11.4 3.1 unlocked) (layer "F.Fab")
(effects (font (size 1 1) (thickness 0.15)))
(tstamp 7415e127-24bc-4666-a29b-ff109d7551a2)
)
(fp_rect (start -2 -0.9) (end 17.6 6.1) (layer "F.SilkS") (width 0.15) (fill none) (tstamp 57bbab45-a75a-4905-a574-87517a61f8db))
(fp_line (start 5.08 -2.54) (end 5.08 7.62) (layer "Dwgs.User") (width 0.12) (tstamp a22d139b-ae36-48a3-b52e-1d45f780278d))
(pad "1" thru_hole roundrect (at 0 0) (size 2 1.524) (drill 0.6) (layers *.Cu *.Mask) (roundrect_rratio 0.25) (tstamp ddbc7909-3eed-4032-bb90-06d3d67deab6))
(pad "2" thru_hole roundrect (at 2.54 0) (size 2 1.524) (drill 0.6) (layers *.Cu *.Mask) (roundrect_rratio 0.25) (tstamp e2c7f9a0-cd9c-40f2-8bc0-64127c765f0d))
(pad "4" thru_hole roundrect (at 7.62 0) (size 2.286 1.524) (drill 0.6) (layers *.Cu *.Mask) (roundrect_rratio 0.25) (tstamp ab22ff25-f082-49df-a551-c9a53e6f86a3))
(pad "6" thru_hole roundrect (at 12.7 0) (size 2.286 1.524) (drill 0.6) (layers *.Cu *.Mask) (roundrect_rratio 0.25) (tstamp 2c7aecb6-ba12-4511-83ea-d194a95071b1))
)

View File

@ -0,0 +1,215 @@
(footprint "B0x0xS"
(version 20250309)
(generator "pcbnew")
(generator_version "9.0")
(layer "F.Cu")
(property "Reference" "REF**"
(at -2.54 2.286 0)
(layer "F.SilkS")
(uuid "ee98884c-b01e-42c7-8815-70c63ca0380a")
(effects
(font
(size 1 1)
(thickness 0.15)
)
)
)
(property "Value" "B0x0xS"
(at 0 -3.048 0)
(layer "F.Fab")
(uuid "1a9a2254-801e-44cc-8499-5009849477a8")
(effects
(font
(size 1 1)
(thickness 0.15)
)
)
)
(property "Datasheet" ""
(at 0 0 0)
(layer "F.Fab")
(hide yes)
(uuid "bc9c3dde-2efe-45e1-bd44-32a6ae7e881e")
(effects
(font
(size 1.27 1.27)
(thickness 0.15)
)
)
)
(property "Description" ""
(at 0 0 0)
(layer "F.Fab")
(hide yes)
(uuid "a468b167-8529-4df4-bd4f-e1bfc8c650fc")
(effects
(font
(size 1.27 1.27)
(thickness 0.15)
)
)
)
(attr through_hole)
(fp_line
(start -5.8 -5.1)
(end -5.8 0.9)
(stroke
(width 0.12)
(type solid)
)
(layer "F.SilkS")
(uuid "91575876-2f5f-4300-a59e-6327bd41978a")
)
(fp_line
(start -5.8 0.9)
(end -0.7112 0.9144)
(stroke
(width 0.15)
(type solid)
)
(layer "F.SilkS")
(uuid "da822648-b16d-46ef-87d0-571b66c556db")
)
(fp_line
(start -0.508 -5.08)
(end -5.8 -5.1)
(stroke
(width 0.15)
(type solid)
)
(layer "F.SilkS")
(uuid "8e59ddde-6d7b-4614-9742-26db8138db0f")
)
(fp_line
(start 5.8 -5.1)
(end 0.508 -5.08)
(stroke
(width 0.15)
(type solid)
)
(layer "F.SilkS")
(uuid "f87c72b9-c305-489a-bd04-b4a4d58b725c")
)
(fp_line
(start 5.8 -5.1)
(end 5.8 0.9)
(stroke
(width 0.12)
(type solid)
)
(layer "F.SilkS")
(uuid "dbc34d16-64b1-40be-9926-084f9486b43d")
)
(fp_line
(start 5.8 0.9)
(end 0.7112 0.9144)
(stroke
(width 0.15)
(type solid)
)
(layer "F.SilkS")
(uuid "0b84b7ec-816f-417e-80c2-0f03b7ee6c7b")
)
(fp_line
(start -0.254 -5.0292)
(end -0.254 1.0668)
(stroke
(width 0.12)
(type solid)
)
(layer "Dwgs.User")
(uuid "a79606de-8ac2-4d48-8694-8906053dee31")
)
(fp_line
(start 0.254 1.0668)
(end 0.254 -5.0292)
(stroke
(width 0.12)
(type solid)
)
(layer "Dwgs.User")
(uuid "935182ad-231d-4492-a2e6-b8ef4f61bdd9")
)
(fp_arc
(start -0.254 -5.0292)
(mid 0 -5.2832)
(end 0.254 -5.0292)
(stroke
(width 0.12)
(type solid)
)
(layer "Dwgs.User")
(uuid "376daf3d-77a6-4454-837b-ecaaa3bfab58")
)
(fp_arc
(start 0.254 1.0668)
(mid 0 1.3208)
(end -0.254 1.0668)
(stroke
(width 0.12)
(type solid)
)
(layer "Dwgs.User")
(uuid "f817554e-83c7-4eb1-9e73-a6b2db3e941a")
)
(pad "1" thru_hole circle
(at -3.81 0)
(size 1.5 1.5)
(drill 0.8)
(layers "*.Cu" "*.Mask")
(remove_unused_layers no)
(tenting
(front none)
(back none)
)
(uuid "3679fd64-6d94-4bd2-ac77-833e9fb0e6b1")
)
(pad "2" thru_hole circle
(at -1.27 0)
(size 1.5 1.5)
(drill 0.8)
(layers "*.Cu" "*.Mask")
(remove_unused_layers no)
(tenting
(front none)
(back none)
)
(uuid "51cfc21e-2343-41b5-b7a1-6cbb380df6a0")
)
(pad "3" thru_hole circle
(at 1.27 0)
(size 1.5 1.5)
(drill 0.8)
(layers "*.Cu" "*.Mask")
(remove_unused_layers no)
(tenting
(front none)
(back none)
)
(uuid "753f1d53-de67-4ec3-9369-8afe92344e33")
)
(pad "4" thru_hole circle
(at 3.81 0)
(size 1.5 1.5)
(drill 0.8)
(layers "*.Cu" "*.Mask")
(remove_unused_layers no)
(tenting
(front none)
(back none)
)
(uuid "ca5c819c-51a9-4cb4-96b3-826dc377af10")
)
(embedded_fonts no)
(model "${KICAD8_3DMODEL_DIR}/Converter_DCDC.3dshapes/Converter_DCDC_Murata_CRE1xxxxxx3C_THT.wrl"
(offset
(xyz -3.85 0 0)
)
(scale
(xyz 1 1 1)
)
(rotate
(xyz -0 -0 -90)
)
)
)

View File

@ -0,0 +1,65 @@
(module DSUB-9_Female_Horizontal_P2.77x2.84mm_EdgePinOffset4.94mm_Housed_MountingHolesOffset7.48mm (layer F.Cu) (tedit 59FEDEE2)
(descr "9-pin D-Sub connector, horizontal/angled (90 deg), THT-mount, female, pitch 2.77x2.84mm, pin-PCB-offset 4.9399999999999995mm, distance of mounting holes 25mm, distance of mounting holes to PCB edge 7.4799999999999995mm, see https://disti-assets.s3.amazonaws.com/tonar/files/datasheets/16730.pdf")
(tags "9-pin D-Sub connector horizontal angled 90deg THT female pitch 2.77x2.84mm pin-PCB-offset 4.9399999999999995mm mounting-holes-distance 25mm mounting-hole-offset 25mm")
(fp_text reference REF** (at -5.54 -3.7) (layer F.SilkS)
(effects (font (size 1 1) (thickness 0.15)))
)
(fp_text value DSUB-9_Female_Horizontal_P2.77x2.84mm_EdgePinOffset4.94mm_Housed_MountingHolesOffset7.48mm (at -5.54 15.85) (layer F.Fab)
(effects (font (size 1 1) (thickness 0.15)))
)
(fp_arc (start -18.04 0.3) (end -19.64 0.3) (angle 180.000000) (layer F.Fab) (width 0.1))
(fp_arc (start 6.96 0.3) (end 5.36 0.3) (angle 180.000000) (layer F.Fab) (width 0.1))
(fp_line (start -20.965 -2.7) (end -20.965 7.78) (layer F.Fab) (width 0.1))
(fp_line (start -20.965 7.78) (end 9.885 7.78) (layer F.Fab) (width 0.1))
(fp_line (start 9.885 7.78) (end 9.885 -2.7) (layer F.Fab) (width 0.1))
(fp_line (start 9.885 -2.7) (end -20.965 -2.7) (layer F.Fab) (width 0.1))
(fp_line (start -20.965 7.78) (end -20.965 8.18) (layer F.Fab) (width 0.1))
(fp_line (start -20.965 8.18) (end 9.885 8.18) (layer F.Fab) (width 0.1))
(fp_line (start 9.885 8.18) (end 9.885 7.78) (layer F.Fab) (width 0.1))
(fp_line (start 9.885 7.78) (end -20.965 7.78) (layer F.Fab) (width 0.1))
(fp_line (start -13.69 8.18) (end -13.69 14.35) (layer F.Fab) (width 0.1))
(fp_line (start -13.69 14.35) (end 2.61 14.35) (layer F.Fab) (width 0.1))
(fp_line (start 2.61 14.35) (end 2.61 8.18) (layer F.Fab) (width 0.1))
(fp_line (start 2.61 8.18) (end -13.69 8.18) (layer F.Fab) (width 0.1))
(fp_line (start -20.54 8.18) (end -20.54 13.18) (layer F.Fab) (width 0.1))
(fp_line (start -20.54 13.18) (end -15.54 13.18) (layer F.Fab) (width 0.1))
(fp_line (start -15.54 13.18) (end -15.54 8.18) (layer F.Fab) (width 0.1))
(fp_line (start -15.54 8.18) (end -20.54 8.18) (layer F.Fab) (width 0.1))
(fp_line (start 4.46 8.18) (end 4.46 13.18) (layer F.Fab) (width 0.1))
(fp_line (start 4.46 13.18) (end 9.46 13.18) (layer F.Fab) (width 0.1))
(fp_line (start 9.46 13.18) (end 9.46 8.18) (layer F.Fab) (width 0.1))
(fp_line (start 9.46 8.18) (end 4.46 8.18) (layer F.Fab) (width 0.1))
(fp_line (start -19.64 7.78) (end -19.64 0.3) (layer F.Fab) (width 0.1))
(fp_line (start -16.44 7.78) (end -16.44 0.3) (layer F.Fab) (width 0.1))
(fp_line (start 5.36 7.78) (end 5.36 0.3) (layer F.Fab) (width 0.1))
(fp_line (start 8.56 7.78) (end 8.56 0.3) (layer F.Fab) (width 0.1))
(fp_line (start -21.025 7.72) (end -21.025 -2.76) (layer F.SilkS) (width 0.12))
(fp_line (start -21.025 -2.76) (end 9.945 -2.76) (layer F.SilkS) (width 0.12))
(fp_line (start 9.945 -2.76) (end 9.945 7.72) (layer F.SilkS) (width 0.12))
(fp_line (start -0.25 -3.654338) (end 0.25 -3.654338) (layer F.SilkS) (width 0.12))
(fp_line (start 0.25 -3.654338) (end 0 -3.221325) (layer F.SilkS) (width 0.12))
(fp_line (start 0 -3.221325) (end -0.25 -3.654338) (layer F.SilkS) (width 0.12))
(fp_line (start -21.5 -3.25) (end -21.5 14.85) (layer F.CrtYd) (width 0.05))
(fp_line (start -21.5 14.85) (end 10.4 14.85) (layer F.CrtYd) (width 0.05))
(fp_line (start 10.4 14.85) (end 10.4 -3.25) (layer F.CrtYd) (width 0.05))
(fp_line (start 10.4 -3.25) (end -21.5 -3.25) (layer F.CrtYd) (width 0.05))
(pad 1 thru_hole rect (at 0 0) (size 1.6 1.6) (drill 1) (layers *.Cu *.Mask))
(pad 2 thru_hole circle (at -2.77 0) (size 1.6 1.6) (drill 1) (layers *.Cu *.Mask))
(pad 3 thru_hole circle (at -5.54 0) (size 1.6 1.6) (drill 1) (layers *.Cu *.Mask))
(pad 4 thru_hole circle (at -8.31 0) (size 1.6 1.6) (drill 1) (layers *.Cu *.Mask))
(pad 5 thru_hole circle (at -11.08 0) (size 1.6 1.6) (drill 1) (layers *.Cu *.Mask))
(pad 6 thru_hole circle (at -1.385 2.84) (size 1.6 1.6) (drill 1) (layers *.Cu *.Mask))
(pad 7 thru_hole circle (at -4.155 2.84) (size 1.6 1.6) (drill 1) (layers *.Cu *.Mask))
(pad 8 thru_hole circle (at -6.925 2.84) (size 1.6 1.6) (drill 1) (layers *.Cu *.Mask))
(pad 9 thru_hole circle (at -9.695 2.84) (size 1.6 1.6) (drill 1) (layers *.Cu *.Mask))
(pad 0 thru_hole circle (at -18.04 0.3) (size 4 4) (drill 3.2) (layers *.Cu *.Mask))
(pad 0 thru_hole circle (at 6.96 0.3) (size 4 4) (drill 3.2) (layers *.Cu *.Mask))
(fp_text user %R (at -5.54 11.265) (layer F.Fab)
(effects (font (size 1 1) (thickness 0.15)))
)
(model ${KISYS3DMOD}/Connector_Dsub.3dshapes/DSUB-9_Female_Horizontal_P2.77x2.84mm_EdgePinOffset4.94mm_Housed_MountingHolesOffset7.48mm.wrl
(at (xyz 0 0 0))
(scale (xyz 1 1 1))
(rotate (xyz 0 0 0))
)
)

View File

@ -0,0 +1,9 @@
(module Hole_3mm (layer F.Cu) (tedit 5913F6E4)
(fp_text reference REF** (at 0 3.81) (layer F.SilkS) hide
(effects (font (size 1 1) (thickness 0.15)))
)
(fp_text value Hole_3mm (at 0 -7.62) (layer F.Fab) hide
(effects (font (size 1 1) (thickness 0.15)))
)
(pad 1 thru_hole circle (at 0 0) (size 5 5) (drill 3) (layers *.Cu *.Mask))
)

File diff suppressed because it is too large Load Diff

Binary file not shown.

After

Width:  |  Height:  |  Size: 733 B

View File

@ -0,0 +1,31 @@
(module RJ9-4P4C (layer F.Cu) (tedit 555F7A30)
(fp_text reference J** (at 0 -10.1346) (layer F.SilkS)
(effects (font (size 1 1) (thickness 0.15)))
)
(fp_text value RJ9-4P4C (at 0 10.2108) (layer F.Fab) hide
(effects (font (size 1 1) (thickness 0.15)))
)
(fp_circle (center 0 0) (end -0.25 0) (layer F.CrtYd) (width 0.05))
(fp_line (start -5.84 -9.25) (end 5.84 -9.25) (layer F.CrtYd) (width 0.05))
(fp_line (start 5.84 -9.25) (end 5.84 9.25) (layer F.CrtYd) (width 0.05))
(fp_line (start 5.84 9.25) (end -5.84 9.25) (layer F.CrtYd) (width 0.05))
(fp_line (start -5.84 9.25) (end -5.84 -9.25) (layer F.CrtYd) (width 0.05))
(fp_line (start 0 -0.35) (end 0 0.35) (layer F.CrtYd) (width 0.05))
(fp_line (start -0.35 0) (end 0.35 0) (layer F.CrtYd) (width 0.05))
(fp_line (start -5.59 9) (end -5.59 -9) (layer F.Fab) (width 0.12))
(fp_line (start -5.59 -9) (end 5.59 -9) (layer F.Fab) (width 0.12))
(fp_line (start 5.59 -9) (end 5.59 9) (layer F.Fab) (width 0.12))
(fp_line (start 5.59 9) (end -5.59 9) (layer F.Fab) (width 0.12))
(fp_line (start -5.59 8.8) (end -5.59 -9) (layer F.SilkS) (width 0.12))
(fp_line (start -5.59 -9) (end 5.59 -9) (layer F.SilkS) (width 0.12))
(fp_line (start 5.59 -9) (end 5.59 8.8) (layer F.SilkS) (width 0.12))
(fp_circle (center 3.81 1.15) (end 5.75 1.15) (layer B.CrtYd) (width 0.05))
(fp_circle (center -3.81 1.15) (end -5.75 1.15) (layer B.CrtYd) (width 0.05))
(fp_circle (center -1.905 -6.12) (end -1.805 -6.12) (layer F.SilkS) (width 0.2))
(pad 1 thru_hole circle (at -1.905 -5.2) (size 1.2 1.2) (drill 0.8) (layers *.Cu *.Mask))
(pad 2 thru_hole circle (at -0.635 -7.74) (size 1.2 1.2) (drill 0.8) (layers *.Cu *.Mask))
(pad 3 thru_hole circle (at 0.635 -5.2) (size 1.2 1.2) (drill 0.8) (layers *.Cu *.Mask))
(pad 4 thru_hole circle (at 1.905 -7.74) (size 1.2 1.2) (drill 0.8) (layers *.Cu *.Mask))
(pad "" np_thru_hole circle (at -3.81 1.15) (size 3.2 3.2) (drill 3.2) (layers *.Cu *.Mask))
(pad "" np_thru_hole circle (at 3.81 1.15) (size 3.2 3.2) (drill 3.2) (layers *.Cu *.Mask))
)

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,5 @@
(sym_lib_table
(version 7)
(lib (name "iso3086")(type "KiCad")(uri "${KIPRJMOD}/iso3086.kicad_sym")(options "")(descr ""))
(lib (name "elements")(type "KiCad")(uri "${KIPRJMOD}/elements.kicad_sym")(options "")(descr ""))
)

View File

@ -27,6 +27,7 @@
volatile uint32_t Tms = 0; volatile uint32_t Tms = 0;
static char inbuff[RBINSZ]; static char inbuff[RBINSZ];
static uint32_t monitT[2] = {0};
/* Called when systick fires */ /* Called when systick fires */
void sys_tick_handler(void){ void sys_tick_handler(void){
@ -47,7 +48,6 @@ static void printResult(BiSS_Frame *result){
} }
static void proc_enc(uint8_t idx){ static void proc_enc(uint8_t idx){
uint8_t encbuf[ENCODER_BUFSZ];
static uint32_t lastMSG[2], gotgood[2], gotwrong[2]; static uint32_t lastMSG[2], gotgood[2], gotwrong[2];
int iface = idx ? I_Y : I_X; int iface = idx ? I_Y : I_X;
char ifacechr = idx ? 'Y' : 'X'; char ifacechr = idx ? 'Y' : 'X';
@ -65,9 +65,11 @@ static void proc_enc(uint8_t idx){
CMDWR("'\n"); CMDWR("'\n");
} }
} }
if(l > 0) spi_start_enc(idx); // start encoder reading on each request from given interface
} }
if(!spi_read_enc(idx, encbuf)) return; uint8_t *encbuf = spi_read_enc(idx);
BiSS_Frame result = parse_biss_frame(encbuf, ENCODER_BUFSZ); if(!encbuf) return;
BiSS_Frame result = parse_biss_frame(encbuf, the_conf.encbufsz);
char *str = result.crc_valid ? u2str(result.data) : NULL; char *str = result.crc_valid ? u2str(result.data) : NULL;
uint8_t testflag = (idx) ? user_pars.testy : user_pars.testx; uint8_t testflag = (idx) ? user_pars.testy : user_pars.testx;
if(CDCready[I_CMD]){ if(CDCready[I_CMD]){
@ -86,11 +88,11 @@ static void proc_enc(uint8_t idx){
if(str) ++gotgood[idx]; if(str) ++gotgood[idx];
else ++gotwrong[idx]; else ++gotwrong[idx];
} }
}else{ }else if(!the_conf.flags.monit){
printResult(&result); printResult(&result);
CMDWR("ENC"); USB_putbyte(I_CMD, ifacechr); CMDWR("ENC"); USB_putbyte(I_CMD, ifacechr);
USB_putbyte(I_CMD, '='); USB_putbyte(I_CMD, '=');
hexdump(I_CMD, encbuf, ENCODER_BUFSZ); hexdump(I_CMD, encbuf, the_conf.encbufsz);
CMDWR(" ("); CMDWR(" (");
if(str) CMDWR(str); if(str) CMDWR(str);
else CMDWR("wrong"); else CMDWR("wrong");
@ -102,22 +104,17 @@ static void proc_enc(uint8_t idx){
USB_putbyte(iface, '\n'); USB_putbyte(iface, '\n');
} }
if(result.error) spi_setup(1+idx); // reinit SPI in case of error if(result.error) spi_setup(1+idx); // reinit SPI in case of error
if(testflag) spi_start_enc(idx); if(the_conf.flags.monit) monitT[idx] = Tms;
else if(testflag) spi_start_enc(idx);
} }
int main(){ int main(){
uint32_t lastT = 0;//, lastS = 0; uint32_t lastT = 0;
StartHSE(); StartHSE();
flashstorage_init(); flashstorage_init();
hw_setup(); hw_setup();
USBPU_OFF(); USBPU_OFF();
SysTick_Config(72000); SysTick_Config(72000);
/*
#ifdef EBUG
usart_setup();
uint32_t tt = 0;
#endif
*/
USB_setup(); USB_setup();
#ifndef EBUG #ifndef EBUG
iwdg_setup(); iwdg_setup();
@ -129,29 +126,18 @@ int main(){
LED_blink(LED0); LED_blink(LED0);
lastT = Tms; lastT = Tms;
} }
/*
#ifdef EBUG
if(Tms != tt){
__disable_irq();
usart_transmit();
tt = Tms;
__enable_irq();
}
#endif
*/
if(CDCready[I_CMD]){ if(CDCready[I_CMD]){
/*if(Tms - lastS > 9999){
USB_sendstr(I_CMD, "Tms=");
USB_sendstr(I_CMD, u2str(Tms));
CMDn();
lastS = Tms;
}*/
int l = USB_receivestr(I_CMD, inbuff, RBINSZ); int l = USB_receivestr(I_CMD, inbuff, RBINSZ);
if(l < 0) CMDWRn("ERROR: CMD USB buffer overflow or string was too long"); if(l < 0) CMDWRn("ERROR: CMD USB buffer overflow or string was too long");
else if(l) parse_cmd(inbuff); else if(l) parse_cmd(inbuff);
} }
proc_enc(0); proc_enc(0);
proc_enc(1); proc_enc(1);
if(the_conf.flags.monit){
for(int i = 0; i < 2; ++i){
if(Tms - monitT[i] >= the_conf.monittime) spi_start_enc(i);
}
}
} }
return 0; return 0;
} }

View File

@ -1,94 +1,4 @@
set FLASH_SIZE 0x10000 set FLASH_SIZE 0x10000
source [find interface/stlink.cfg] source [find interface/stlink.cfg]
source [find target/stm32f1x.cfg]
# script for stm32f1x family
#
# stm32 devices support both JTAG and SWD transports.
#
source [find target/swj-dp.tcl]
source [find mem_helper.tcl]
if { [info exists CHIPNAME] } {
set _CHIPNAME $CHIPNAME
} else {
set _CHIPNAME stm32f1x
}
set _ENDIAN little
# Work-area is a space in RAM used for flash programming
# By default use 4kB (as found on some STM32F100s)
if { [info exists WORKAREASIZE] } {
set _WORKAREASIZE $WORKAREASIZE
} else {
set _WORKAREASIZE 0x1000
}
# Allow overriding the Flash bank size
if { [info exists FLASH_SIZE] } {
set _FLASH_SIZE $FLASH_SIZE
} else {
# autodetect size
set _FLASH_SIZE 0
}
#jtag scan chain
if { [info exists CPUTAPID] } {
set _CPUTAPID $CPUTAPID
} else {
if { [using_jtag] } {
# See STM Document RM0008 Section 26.6.3
set _CPUTAPID 0x2ba01477
} {
# this is the SW-DP tap id not the jtag tap id
set _CPUTAPID 0x2ba01477
}
}
swj_newdap $_CHIPNAME cpu -irlen 4 -ircapture 0x1 -irmask 0xf -expected-id $_CPUTAPID
dap create $_CHIPNAME.dap -chain-position $_CHIPNAME.cpu
if {[using_jtag]} {
jtag newtap $_CHIPNAME bs -irlen 5
}
set _TARGETNAME $_CHIPNAME.cpu
target create $_TARGETNAME cortex_m -endian $_ENDIAN -dap $_CHIPNAME.dap
$_TARGETNAME configure -work-area-phys 0x20000000 -work-area-size $_WORKAREASIZE -work-area-backup 0
# flash size will be probed
set _FLASHNAME $_CHIPNAME.flash
flash bank $_FLASHNAME stm32f1x 0x08000000 $_FLASH_SIZE 0 0 $_TARGETNAME
# JTAG speed should be <= F_CPU/6. F_CPU after reset is 8MHz, so use F_JTAG = 1MHz
adapter_khz 1000
adapter_nsrst_delay 100
if {[using_jtag]} {
jtag_ntrst_delay 100
}
reset_config srst_nogate
if {![using_hla]} {
# if srst is not fitted use SYSRESETREQ to
# perform a soft reset
cortex_m reset_config sysresetreq
}
$_TARGETNAME configure -event examine-end {
# DBGMCU_CR |= DBG_WWDG_STOP | DBG_IWDG_STOP |
# DBG_STANDBY | DBG_STOP | DBG_SLEEP
mmw 0xE0042004 0x00000307 0
}
$_TARGETNAME configure -event trace-config {
# Set TRACE_IOEN; TRACE_MODE is set to async; when using sync
# change this value accordingly to configure trace pins
# assignment
mmw 0xE0042004 0x00000020 0
}

View File

@ -0,0 +1,94 @@
set FLASH_SIZE 0x10000
source [find interface/stlink.cfg]
# script for stm32f1x family
#
# stm32 devices support both JTAG and SWD transports.
#
source [find target/swj-dp.tcl]
source [find mem_helper.tcl]
if { [info exists CHIPNAME] } {
set _CHIPNAME $CHIPNAME
} else {
set _CHIPNAME stm32f1x
}
set _ENDIAN little
# Work-area is a space in RAM used for flash programming
# By default use 4kB (as found on some STM32F100s)
if { [info exists WORKAREASIZE] } {
set _WORKAREASIZE $WORKAREASIZE
} else {
set _WORKAREASIZE 0x1000
}
# Allow overriding the Flash bank size
if { [info exists FLASH_SIZE] } {
set _FLASH_SIZE $FLASH_SIZE
} else {
# autodetect size
set _FLASH_SIZE 0
}
#jtag scan chain
if { [info exists CPUTAPID] } {
set _CPUTAPID $CPUTAPID
} else {
if { [using_jtag] } {
# See STM Document RM0008 Section 26.6.3
set _CPUTAPID 0x2ba01477
} {
# this is the SW-DP tap id not the jtag tap id
set _CPUTAPID 0x2ba01477
}
}
swj_newdap $_CHIPNAME cpu -irlen 4 -ircapture 0x1 -irmask 0xf -expected-id $_CPUTAPID
dap create $_CHIPNAME.dap -chain-position $_CHIPNAME.cpu
if {[using_jtag]} {
jtag newtap $_CHIPNAME bs -irlen 5
}
set _TARGETNAME $_CHIPNAME.cpu
target create $_TARGETNAME cortex_m -endian $_ENDIAN -dap $_CHIPNAME.dap
$_TARGETNAME configure -work-area-phys 0x20000000 -work-area-size $_WORKAREASIZE -work-area-backup 0
# flash size will be probed
set _FLASHNAME $_CHIPNAME.flash
flash bank $_FLASHNAME stm32f1x 0x08000000 $_FLASH_SIZE 0 0 $_TARGETNAME
# JTAG speed should be <= F_CPU/6. F_CPU after reset is 8MHz, so use F_JTAG = 1MHz
adapter_khz 1000
adapter_nsrst_delay 100
if {[using_jtag]} {
jtag_ntrst_delay 100
}
reset_config srst_nogate
if {![using_hla]} {
# if srst is not fitted use SYSRESETREQ to
# perform a soft reset
cortex_m reset_config sysresetreq
}
$_TARGETNAME configure -event examine-end {
# DBGMCU_CR |= DBG_WWDG_STOP | DBG_IWDG_STOP |
# DBG_STANDBY | DBG_STOP | DBG_SLEEP
mmw 0xE0042004 0x00000307 0
}
$_TARGETNAME configure -event trace-config {
# Set TRACE_IOEN; TRACE_MODE is set to async; when using sync
# change this value accordingly to configure trace pins
# assignment
mmw 0xE0042004 0x00000020 0
}

View File

@ -72,6 +72,11 @@ typedef enum{
C_encbits, C_encbits,
C_testX, C_testX,
C_testY, C_testY,
C_encbufsz,
C_minzeros,
C_maxzeros,
C_autom,
C_amperiod,
C_AMOUNT C_AMOUNT
} cmd_e; } cmd_e;
@ -223,58 +228,64 @@ static errcode_e spideinit(_U_ cmd_e idx, _U_ char *par){
return ERR_SILENCE; return ERR_SILENCE;
} }
static errcode_e setflags(cmd_e idx, char *par){ static errcode_e setuintpar(cmd_e idx, char *par){
uint32_t val;
if(par){ if(par){
if(*par < '0' || *par > '9') return ERR_BADPAR; if(par == getnum(par, &val)) return ERR_BADPAR;
uint8_t val = *par - '0';
switch(idx){ switch(idx){
case C_cpha: case C_br:
if(val > 1) return ERR_BADPAR; if(val == 0 || val > 7) return ERR_BADPAR;
the_conf.flags.CPHA = val; the_conf.flags.BR = val;
break; break;
case C_cpol: case C_encbits:
if(val > 1) return ERR_BADPAR; if(val < ENCRESOL_MIN || val > ENCRESOL_MAX) return ERR_BADPAR; // don't support less than 8 of more than 32
the_conf.flags.CPOL = val; the_conf.encbits = val;
break; break;
case C_encbufsz:
if(val < 8 || val > ENCODER_BUFSZ_MAX) return ERR_BADPAR;
the_conf.encbufsz = val;
break;
case C_minzeros:
if(val < MINZEROS_MIN || val > MINZEROS_MAX) return ERR_BADPAR;
the_conf.minzeros = val;
break;
case C_maxzeros:
if(val < MAXZEROS_MIN || val > MAXZEROS_MAX) return ERR_BADPAR;
the_conf.maxzeros = val;
break;
case C_amperiod:
if(val > 255 || val == 0) return ERR_BADPAR;
the_conf.monittime = val;
break;
default:
return ERR_BADCMD;
}
}
CMDWR(commands[idx].cmd);
USB_putbyte(I_CMD, '=');
switch(idx){
case C_br: case C_br:
if(val == 0 || val > 7) return ERR_BADPAR; val = the_conf.flags.BR;
the_conf.flags.BR = val; break;
case C_encbits:
val = the_conf.encbits;
break;
case C_encbufsz:
val = the_conf.encbufsz;
break;
case C_minzeros:
val = the_conf.minzeros;
break;
case C_maxzeros:
val = the_conf.maxzeros;
break;
case C_amperiod:
val = the_conf.monittime;
break; break;
default: default:
return ERR_BADCMD; return ERR_BADCMD;
}
} }
uint8_t val = 0; CMDWR(u2str(val));
switch(idx){
case C_cpha:
val = the_conf.flags.CPHA;
break;
case C_cpol:
val = the_conf.flags.CPOL;
break;
case C_br:
val = the_conf.flags.BR;
break;
default:
return ERR_BADCMD;
}
CMDWR(commands[idx].cmd);
USB_putbyte(I_CMD, '=');
USB_putbyte(I_CMD, '0' + val);
CMDn();
return ERR_SILENCE;
}
static errcode_e encbits(cmd_e idx, char *par){
if(par){
uint32_t N;
if(par == getnum(par, &N)) return ERR_BADPAR;
if(N < 26 || N > 32) return ERR_BADPAR; // don't support less than 26 of more than 32
the_conf.encbits = N;
}
CMDWR(commands[idx].cmd);
USB_putbyte(I_CMD, '=');
CMDWR(u2str(the_conf.encbits));
CMDn(); CMDn();
return ERR_SILENCE; return ERR_SILENCE;
} }
@ -285,25 +296,43 @@ static errcode_e setboolpar(cmd_e idx, char *par){
if(*par != '0' && *par != '1') return ERR_BADPAR; if(*par != '0' && *par != '1') return ERR_BADPAR;
val = *par - '0'; val = *par - '0';
switch(idx){ switch(idx){
case C_cpha:
the_conf.flags.CPHA = val;
break;
case C_cpol:
the_conf.flags.CPOL = val;
break;
case C_testX: case C_testX:
user_pars.testx = val; user_pars.testx = val;
break; if(val) spi_start_enc(0);
break;
case C_testY: case C_testY:
user_pars.testy = val; user_pars.testy = val;
break; if(val) spi_start_enc(1);
break;
case C_autom:
the_conf.flags.monit = val;
break;
default: default:
return ERR_BADCMD; return ERR_BADCMD;
} }
} }
switch(idx){ switch(idx){
case C_cpha:
val = the_conf.flags.CPHA;
break;
case C_cpol:
val = the_conf.flags.CPOL;
break;
case C_testX: case C_testX:
val = user_pars.testx; val = user_pars.testx;
if(val) spi_start_enc(0); break;
break;
case C_testY: case C_testY:
val = user_pars.testy; val = user_pars.testy;
if(val) spi_start_enc(1); break;
break; case C_autom:
val = the_conf.flags.monit;
break;
default: default:
return ERR_BADCMD; return ERR_BADCMD;
} }
@ -320,10 +349,15 @@ static errcode_e dumpconf(cmd_e _U_ idx, char _U_ *par){
CMDn(); CMDn();
for(int i = 0; i < bTotNumEndpoints; ++i) for(int i = 0; i < bTotNumEndpoints; ++i)
setiface(C_setiface1 + i, NULL); setiface(C_setiface1 + i, NULL);
setflags(C_br, NULL); setboolpar(C_autom, NULL);
setflags(C_cpha, NULL); setuintpar(C_amperiod, NULL);
setflags(C_cpol, NULL); setuintpar(C_br, NULL);
encbits(C_encbits, NULL); setboolpar(C_cpha, NULL);
setboolpar(C_cpol, NULL);
setuintpar(C_encbits, NULL);
setuintpar(C_encbufsz, NULL);
setuintpar(C_maxzeros, NULL);
setuintpar(C_minzeros, NULL);
return ERR_SILENCE; return ERR_SILENCE;
} }
@ -347,12 +381,17 @@ static const funcdescr_t commands[C_AMOUNT] = {
[C_spistat] = {"spistat", spistat}, [C_spistat] = {"spistat", spistat},
[C_spiinit] = {"spiinit", spiinit}, [C_spiinit] = {"spiinit", spiinit},
[C_spideinit] = {"spideinit", spideinit}, [C_spideinit] = {"spideinit", spideinit},
[C_cpol] = {"CPOL", setflags}, [C_cpol] = {"CPOL", setboolpar},
[C_cpha] = {"CPHA", setflags}, [C_cpha] = {"CPHA", setboolpar},
[C_br] = {"BR", setflags}, [C_br] = {"BR", setuintpar},
[C_encbits] = {"encbits", encbits}, [C_encbits] = {"encbits", setuintpar},
[C_testX] = {"testx", setboolpar}, [C_testX] = {"testx", setboolpar},
[C_testY] = {"testy", setboolpar}, [C_testY] = {"testy", setboolpar},
[C_encbufsz] = {"encbufsz", setuintpar},
[C_minzeros] = {"minzeros", setuintpar},
[C_maxzeros] = {"maxzeros", setuintpar},
[C_autom] = {"autom", setboolpar},
[C_amperiod] = {"amperiod", setuintpar},
}; };
typedef struct{ typedef struct{
@ -362,28 +401,33 @@ typedef struct{
// SHOUL be sorted and grouped // SHOUL be sorted and grouped
static const help_t helpmessages[] = { static const help_t helpmessages[] = {
{-1, "Configuration"}, {-1, "Base commands"},
{C_dumpconf, "dump current configuration"}, {C_encstart, "read both encoders once"},
{C_erasestorage, "erase full storage or current page (=n)"}, {C_encX, "read X encoder once"},
{C_setiface1, "set name of first (command) interface"}, {C_encY, "read Y encoder once"},
{C_setiface2, "set name of second (axis X) interface"},
{C_setiface3, "set name of third (axis Y) interface"},
{C_storeconf, "store configuration in flash memory"},
{-1, "Different commands"},
{C_dummy, "dummy integer setter/getter"},
{C_encstart, "start reading encoders"},
{C_encX, "read only X encoder"},
{C_encY, "read only Y encoder"},
{C_help, "show this help"}, {C_help, "show this help"},
{C_reset, "reset MCU"}, {C_reset, "reset MCU"},
{C_spideinit, "deinit SPI"}, {C_spideinit, "deinit SPI"},
{C_spiinit, "init SPI"}, {C_spiinit, "init SPI"},
{C_spistat, "get status of both SPI interfaces"}, {C_spistat, "get status of both SPI interfaces"},
{-1, "Debug"}, {-1, "Configuration"},
{C_autom, "turn on or off automonitoring"},
{C_amperiod, "period (ms) of monitoring, 1..255"},
{C_br, "change SPI BR register (1 - 18MHz ... 7 - 281kHz)"}, {C_br, "change SPI BR register (1 - 18MHz ... 7 - 281kHz)"},
{C_cpha, "change CPHA value (0/1)"}, {C_cpha, "change CPHA value (0/1)"},
{C_cpol, "change CPOL value (0/1)"}, {C_cpol, "change CPOL value (0/1)"},
{C_encbits, "set encoder data bits amount"}, {C_dumpconf, "dump current configuration"},
{C_encbits, "set encoder data bits amount (26/32)"},
{C_encbufsz, "change encoder auxiliary buffer size (8..32 bytes)"},
{C_erasestorage, "erase full storage or current page (=n)"},
{C_maxzeros, "maximal amount of zeros in preamble"},
{C_minzeros, "minimal amount of zeros in preamble"},
{C_setiface1, "set name of first (command) interface"},
{C_setiface2, "set name of second (axis X) interface"},
{C_setiface3, "set name of third (axis Y) interface"},
{C_storeconf, "store configuration in flash memory"},
{-1, "Debug commands"},
{C_dummy, "dummy integer setter/getter"},
{C_fin, "reinit flash"}, {C_fin, "reinit flash"},
{C_sendX, "send text string to X encoder's terminal"}, {C_sendX, "send text string to X encoder's terminal"},
{C_sendY, "send text string to Y encoder's terminal"}, {C_sendY, "send text string to Y encoder's terminal"},

View File

@ -34,7 +34,7 @@ static volatile SPI_TypeDef* const SPIs[AMOUNT_OF_SPI+1] = {NULL, SPI1, SPI2};
static volatile DMA_Channel_TypeDef * const DMAs[AMOUNT_OF_SPI+1] = {NULL, DMA1_Channel2, DMA1_Channel4}; static volatile DMA_Channel_TypeDef * const DMAs[AMOUNT_OF_SPI+1] = {NULL, DMA1_Channel2, DMA1_Channel4};
#define WAITX(x) do{volatile uint32_t wctr = 0; while((x) && (++wctr < 3600)) IWDG->KR = IWDG_REFRESH; if(wctr==3600){ DBG("timeout"); return 0;}}while(0) #define WAITX(x) do{volatile uint32_t wctr = 0; while((x) && (++wctr < 3600)) IWDG->KR = IWDG_REFRESH; if(wctr==3600){ DBG("timeout"); return 0;}}while(0)
static uint8_t encoderbuf[AMOUNT_OF_SPI][ENCODER_BUFSZ] = {0}; static uint8_t encoderbuf[AMOUNT_OF_SPI][ENCODER_BUFSZ_MAX] = {0};
static uint8_t freshdata[AMOUNT_OF_SPI] = {0}; static uint8_t freshdata[AMOUNT_OF_SPI] = {0};
// init SPI to work RX-only with DMA // init SPI to work RX-only with DMA
@ -81,8 +81,6 @@ void spi_onoff(uint8_t idx, uint8_t on){
CHKIDX(idx); CHKIDX(idx);
volatile SPI_TypeDef *SPI = SPIs[idx]; volatile SPI_TypeDef *SPI = SPIs[idx];
if(on){ if(on){
//DBGs(u2str(idx));
//DBG("turn on SPI");
SPI->CR1 |= SPI_CR1_SPE; SPI->CR1 |= SPI_CR1_SPE;
spi_status[idx] = SPI_BUSY; spi_status[idx] = SPI_BUSY;
}else{ }else{
@ -114,20 +112,15 @@ static int spi_waitbsy(uint8_t idx){
DBG("Busy - turn off"); DBG("Busy - turn off");
spi_onoff(idx, 0); // turn off SPI if it's busy spi_onoff(idx, 0); // turn off SPI if it's busy
} }
//DBGs(u2str(idx));
//DBG("wait busy");
//WAITX(SPIs[idx]->SR & SPI_SR_BSY);
return 1; return 1;
} }
// just copy last read encoder value into `buf` // just copy last read encoder value into `buf`
// @return TRUE if got fresh data // @return pointer to buffer if got fresh data
int spi_read_enc(uint8_t encno, uint8_t buf[ENCODER_BUFSZ]){ uint8_t *spi_read_enc(uint8_t encno){
if(encno > 1 || !freshdata[encno]) return FALSE; if(encno > 1 || !freshdata[encno]) return NULL;
//DBGs(u2str(encno)); DBG("Read encoder data");
memcpy(buf, encoderbuf[encno], ENCODER_BUFSZ);
freshdata[encno] = 0; // clear fresh status freshdata[encno] = 0; // clear fresh status
return TRUE; return encoderbuf[encno];
} }
// start encoder reading over DMA // start encoder reading over DMA
@ -135,16 +128,12 @@ int spi_read_enc(uint8_t encno, uint8_t buf[ENCODER_BUFSZ]){
// here `encodernum` is 0 (SPI1) or 1 (SPI2), not 1/2 as SPI index! // here `encodernum` is 0 (SPI1) or 1 (SPI2), not 1/2 as SPI index!
int spi_start_enc(int encodernum){ int spi_start_enc(int encodernum){
int spiidx = encodernum + 1; int spiidx = encodernum + 1;
//DBG("start enc");
if(spiidx < 1 || spiidx > AMOUNT_OF_SPI) return FALSE; if(spiidx < 1 || spiidx > AMOUNT_OF_SPI) return FALSE;
if(spi_status[spiidx] != SPI_READY) return FALSE; if(spi_status[spiidx] != SPI_READY) return FALSE;
if(!spi_waitbsy(spiidx)) return FALSE; if(!spi_waitbsy(spiidx)) return FALSE;
if(SPI1->CR1 & SPI_CR1_SPE){ DBG("spi1 works!");}
if(SPI2->CR1 & SPI_CR1_SPE){ DBG("spi2 works!");}
volatile DMA_Channel_TypeDef *DMA = DMAs[spiidx]; volatile DMA_Channel_TypeDef *DMA = DMAs[spiidx];
DMA->CMAR = (uint32_t) encoderbuf[encodernum]; DMA->CMAR = (uint32_t) encoderbuf[encodernum];
DMA->CNDTR = ENCODER_BUFSZ; DMA->CNDTR = the_conf.encbufsz;
//DBG("turn on spi");
spi_onoff(spiidx, 1); spi_onoff(spiidx, 1);
DMA->CCR |= DMA_CCR_EN; DMA->CCR |= DMA_CCR_EN;
return TRUE; return TRUE;
@ -159,12 +148,8 @@ void dma1_channel2_isr(){
DMA1->IFCR = DMA_IFCR_CTEIF2; DMA1->IFCR = DMA_IFCR_CTEIF2;
} }
if(DMA1->ISR & DMA_ISR_TCIF2){ if(DMA1->ISR & DMA_ISR_TCIF2){
//uint32_t ctr = TIM2->CNT;
DMA1->IFCR = DMA_IFCR_CTCIF2; DMA1->IFCR = DMA_IFCR_CTCIF2;
freshdata[0] = 1; freshdata[0] = 1;
//encoderbuf[5] = (ctr >> 16) & 0xff;
//encoderbuf[6] = (ctr >> 8 ) & 0xff;
//encoderbuf[7] = (ctr >> 0 ) & 0xff;
} }
spi_status[1] = SPI_READY; spi_status[1] = SPI_READY;
} }

View File

@ -2,9 +2,13 @@
#pragma once #pragma once
#include <stdint.h> #include <stdint.h>
// two SPI interfaces for two sensors
#define AMOUNT_OF_SPI (2) #define AMOUNT_OF_SPI (2)
// static buffer size
#define ENCODER_BUFSZ (12) #define ENCODER_BUFSZ_MAX (32)
// encoder resolution
#define ENCRESOL_MIN (8)
#define ENCRESOL_MAX (32)
typedef enum{ typedef enum{
SPI_NOTREADY, SPI_NOTREADY,
@ -18,4 +22,4 @@ void spi_onoff(uint8_t idx, uint8_t on);
void spi_deinit(uint8_t idx); void spi_deinit(uint8_t idx);
void spi_setup(uint8_t idx); void spi_setup(uint8_t idx);
int spi_start_enc(int encodernum); int spi_start_enc(int encodernum);
int spi_read_enc(uint8_t encno, uint8_t buf[ENCODER_BUFSZ]); uint8_t *spi_read_enc(uint8_t encno);

22
F1:F103/BISS_C_encoders/testDev Executable file
View File

@ -0,0 +1,22 @@
#!/bin/bash
trap ctrl_c INT
function ctrl_c() {
echo "Terminated - exit" >&2
exit 0
}
if [[ $# != 1 ]]; then
echo "Point device name, e.g. /dev/encoder_X0" >&2
exit 1
fi
stty -F $1 -echo
START=$(date +%s)
while read VAL; do
CUR=$(($(date +%s) - $START))
echo -e "$CUR.$(date +%N)\t$VAL"
done < $1

View File

@ -1,100 +0,0 @@
/*
* usart.c
*
* Copyright 2018 Edward V. Emelianoff <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*/
#include <string.h>
#include "stm32f1.h"
#include "usart.h"
#include "ringbuffer.h"
extern volatile uint32_t Tms;
// buffers for out ringbuffer and DMA send
static uint8_t buf[UARTBUFSZ], txbuf[UARTBUFSZ];
static ringbuffer ringbuf = {.data = buf, .length = UARTBUFSZ};
static volatile int usart_txrdy = 1; // transmission done
// transmit current tbuf
void usart_transmit(){
if(RB_hasbyte(&ringbuf, '\n') < 0 || !usart_txrdy) return;
int L = 0, l = 0;
do{
l = RB_readto(&ringbuf, '\n', txbuf + L, UARTBUFSZ - L);
if(l > 0) L += l;
}while(l > 0 && L < UARTBUFSZ);
if(L < 1) return;
usart_txrdy = 0;
if(L < UARTBUFSZ-1){
txbuf[L++] = '$'; txbuf[L++] = '\n';
}
DMA1_Channel4->CCR &= ~DMA_CCR_EN;
DMA1_Channel4->CMAR = (uint32_t) txbuf; // mem
DMA1_Channel4->CNDTR = L;
DMA1_Channel4->CCR |= DMA_CCR_EN;
}
void usart_putchar(const char ch){
RB_write(&ringbuf, (const uint8_t*)&ch, 1);
}
void usart_send(const char *str){
int l = strlen(str);
if(RB_datalen(&ringbuf) > UARTBUFSZ/2) usart_transmit();
RB_write(&ringbuf, (const uint8_t*)str, l);
}
/*
* USART speed: baudrate = Fck/(USARTDIV)
* USARTDIV stored in USART->BRR
*
* for 72MHz USARTDIV=72000/f(kboud); so for 115200 USARTDIV=72000/115.2=625 -> BRR=0x271
* 9600: BRR = 7500 (0x1D4C)
*/
void usart_setup(){
uint32_t tmout = 16000000;
// PA9 - Tx, PA10 - Rx
RCC->APB2ENR |= RCC_APB2ENR_IOPAEN | RCC_APB2ENR_USART1EN | RCC_APB2ENR_AFIOEN;
RCC->AHBENR |= RCC_AHBENR_DMA1EN;
GPIOA->CRH |= CRH(9, CNF_AFPP|MODE_NORMAL) | CRH(10, CNF_FLINPUT|MODE_INPUT);
// USART1 Tx DMA - Channel4 (Rx - channel 5)
DMA1_Channel4->CPAR = (uint32_t) &USART1->DR; // periph
DMA1_Channel4->CCR |= DMA_CCR_MINC | DMA_CCR_DIR | DMA_CCR_TCIE; // 8bit, mem++, mem->per, transcompl irq
// Tx CNDTR set @ each transmission due to data size
NVIC_SetPriority(DMA1_Channel4_IRQn, 3);
NVIC_EnableIRQ(DMA1_Channel4_IRQn);
NVIC_SetPriority(USART1_IRQn, 0);
// setup usart1
USART1->BRR = 72000000 / 4000000;
USART1->CR1 = USART_CR1_TE | USART_CR1_UE; // 1start,8data,nstop; enable Rx,Tx,USART
while(!(USART1->SR & USART_SR_TC)){if(--tmout == 0) break;} // polling idle frame Transmission
USART1->SR = 0; // clear flags
USART1->CR1 |= USART_CR1_RXNEIE; // allow Rx IRQ
USART1->CR3 = USART_CR3_DMAT; // enable DMA Tx
}
void dma1_channel4_isr(){
if(DMA1->ISR & DMA_ISR_TCIF4){ // Tx
DMA1->IFCR = DMA_IFCR_CTCIF4; // clear TC flag
usart_txrdy = 1;
}
}

View File

@ -1,2 +1,2 @@
#define BUILD_NUMBER "91" #define BUILD_NUMBER "96"
#define BUILD_DATE "2025-04-02" #define BUILD_DATE "2025-04-04"

View File

@ -78,13 +78,19 @@ static void chkin(uint8_t ifno){
static void send_next(uint8_t ifno){ static void send_next(uint8_t ifno){
uint8_t usbbuff[USB_TXBUFSZ]; uint8_t usbbuff[USB_TXBUFSZ];
int buflen = RB_read((ringbuffer*)&rbout[ifno], (uint8_t*)usbbuff, USB_TXBUFSZ); int buflen = RB_read((ringbuffer*)&rbout[ifno], (uint8_t*)usbbuff, USB_TXBUFSZ);
if(!CDCready[ifno]){
lastdsz[ifno] = -1;
return;
}
if(buflen == 0){ if(buflen == 0){
if(lastdsz[ifno] == 64) EP_Write(1+ifno, NULL, 0); // send ZLP after 64 bits packet when nothing more to send if(lastdsz[ifno] == USB_TXBUFSZ){
lastdsz[ifno] = 0; EP_Write(1+ifno, NULL, 0); // send ZLP after 64 bits packet when nothing more to send
lastdsz[ifno] = 0;
}else lastdsz[ifno] = -1; // OK. User can start sending data
return; return;
}else if(buflen < 0){ }else if(buflen < 0){
DBG("Buff busy"); DBG("Buff busy");
lastdsz[ifno] = 0; lastdsz[ifno] = -1;
return; return;
} }
DBG("Got data in buf"); DBG("Got data in buf");
@ -221,14 +227,17 @@ int USB_send(uint8_t ifno, const uint8_t *buf, int len){
if(!buf || !CDCready[ifno] || !len) return FALSE; if(!buf || !CDCready[ifno] || !len) return FALSE;
DBG("USB_send"); DBG("USB_send");
while(len){ while(len){
if(!CDCready[ifno]) return FALSE;
IWDG->KR = IWDG_REFRESH; IWDG->KR = IWDG_REFRESH;
int a = RB_write((ringbuffer*)&rbout[ifno], buf, len); int a = RB_write((ringbuffer*)&rbout[ifno], buf, len);
if(lastdsz[ifno] == 0) send_next(ifno); // need to run manually - all data sent, so no IRQ on IN
if(a > 0){ if(a > 0){
len -= a; len -= a;
buf += a; buf += a;
} else if (a < 0) continue; // do nothing if buffer is in reading state }else if(a == 0){ // overfull
if(lastdsz[ifno] < 0) send_next(ifno);
}
} }
if(buf[len-1] == '\n' && lastdsz[ifno] < 0) send_next(ifno);
return TRUE; return TRUE;
} }
@ -236,10 +245,15 @@ int USB_putbyte(uint8_t ifno, uint8_t byte){
if(!CDCready[ifno]) return FALSE; if(!CDCready[ifno]) return FALSE;
int l = 0; int l = 0;
while((l = RB_write((ringbuffer*)&rbout[ifno], &byte, 1)) != 1){ while((l = RB_write((ringbuffer*)&rbout[ifno], &byte, 1)) != 1){
if(!CDCready[ifno]) return FALSE;
IWDG->KR = IWDG_REFRESH; IWDG->KR = IWDG_REFRESH;
if(lastdsz[ifno] == 0) send_next(ifno); // need to run manually - all data sent, so no IRQ on IN if(l == 0){ // overfull
if(l < 0) continue; if(lastdsz[ifno] < 0) send_next(ifno);
continue;
}
} }
// send line if got EOL
if(byte == '\n' && lastdsz[ifno] < 0) send_next(ifno);
return TRUE; return TRUE;
} }

View File

@ -75,13 +75,19 @@ static void chkin(){
static void send_next(){ static void send_next(){
uint8_t usbbuff[USB_TXBUFSZ]; uint8_t usbbuff[USB_TXBUFSZ];
int buflen = RB_read((ringbuffer*)&rbout, (uint8_t*)usbbuff, USB_TXBUFSZ); int buflen = RB_read((ringbuffer*)&rbout, (uint8_t*)usbbuff, USB_TXBUFSZ);
if(!CDCready){
lastdsz = -1;
return;
}
if(buflen == 0){ if(buflen == 0){
if(lastdsz == 64) EP_Write(1, NULL, 0); // send ZLP after 64 bits packet when nothing more to send if(lastdsz == USB_TXBUFSZ){
lastdsz = 0; EP_Write(1, NULL, 0); // send ZLP after 64 bits packet when nothing more to send
lastdsz = 0;
}else lastdsz = -1;
return; return;
}else if(buflen < 0){ }else if(buflen < 0){
DBG("Buff busy"); DBG("Buff busy");
lastdsz = 0; lastdsz = -1;
return; return;
} }
DBG("Got data in buf"); DBG("Got data in buf");
@ -193,14 +199,17 @@ int USB_send(const uint8_t *buf, int len){
if(!buf || !CDCready || !len) return FALSE; if(!buf || !CDCready || !len) return FALSE;
DBG("USB_send"); DBG("USB_send");
while(len){ while(len){
if(!CDCready) return FALSE;
IWDG->KR = IWDG_REFRESH; IWDG->KR = IWDG_REFRESH;
int a = RB_write((ringbuffer*)&rbout, buf, len); int a = RB_write((ringbuffer*)&rbout, buf, len);
if(lastdsz == 0) send_next(); // need to run manually - all data sent, so no IRQ on IN
if(a > 0){ if(a > 0){
len -= a; len -= a;
buf += a; buf += a;
} else if (a < 0) continue; // do nothing if buffer is in reading state }else if(a == 0){ // overfull
if(lastdsz < 0) send_next();
}
} }
if(buf[len-1] == '\n' && lastdsz < 0) send_next();
return TRUE; return TRUE;
} }
@ -208,10 +217,14 @@ int USB_putbyte(uint8_t byte){
if(!CDCready) return FALSE; if(!CDCready) return FALSE;
int l = 0; int l = 0;
while((l = RB_write((ringbuffer*)&rbout, &byte, 1)) != 1){ while((l = RB_write((ringbuffer*)&rbout, &byte, 1)) != 1){
if(!CDCready) return FALSE;
IWDG->KR = IWDG_REFRESH; IWDG->KR = IWDG_REFRESH;
if(lastdsz == 0) send_next(); // need to run manually - all data sent, so no IRQ on IN if(l == 0){ // overfull
if(l < 0) continue; if(lastdsz < 0) send_next();
continue;
}
} }
if(byte == '\n' && lastdsz < 0) send_next();
return TRUE; return TRUE;
} }

View File

@ -81,12 +81,18 @@ static void chkin(){
static void send_next(){ static void send_next(){
uint8_t usbbuff[USB_TXBUFSZ]; uint8_t usbbuff[USB_TXBUFSZ];
int buflen = RB_read((ringbuffer*)&rbout, (uint8_t*)usbbuff, USB_TXBUFSZ); int buflen = RB_read((ringbuffer*)&rbout, (uint8_t*)usbbuff, USB_TXBUFSZ);
if(!CDCready){
lastdsz = -1;
return;
}
if(buflen == 0){ if(buflen == 0){
if(lastdsz == 64) EP_Write(3, NULL, 0); // send ZLP after 64 bits packet when nothing more to send if(lastdsz == 64){
lastdsz = 0; EP_Write(3, NULL, 0); // send ZLP after 64 bits packet when nothing more to send
lastdsz = 0;
} else lastdsz = -1; // OK. User can start sending data
return; return;
}else if(buflen < 0){ }else if(buflen < 0){
lastdsz = 0; lastdsz = -1;
return; return;
} }
EP_Write(3, (uint8_t*)usbbuff, buflen); EP_Write(3, (uint8_t*)usbbuff, buflen);
@ -231,16 +237,19 @@ int USB_sendall(){
// put `buf` into queue to send // put `buf` into queue to send
int USB_send(const uint8_t *buf, int len){ int USB_send(const uint8_t *buf, int len){
if(!buf || !CDCready || !len) return FALSE; if(!buf || !CDCready || !len) return FALSE;
DBG("send"); DBG("USB_send");
while(len){ while(len){
if(!CDCready) return FALSE;
IWDG->KR = IWDG_REFRESH; IWDG->KR = IWDG_REFRESH;
int a = RB_write((ringbuffer*)&rbout, buf, len); int a = RB_write((ringbuffer*)&rbout, buf, len);
if(lastdsz == 0) send_next(); // need to run manually - all data sent, so no IRQ on IN
if(a > 0){ if(a > 0){
len -= a; len -= a;
buf += a; buf += a;
} else if (a < 0) continue; // do nothing if buffer is in reading state }else if(a == 0){ // overfull
if(lastdsz < 0) send_next();
} }
}
if(buf[len-1] == '\n' && lastdsz < 0) send_next();
return TRUE; return TRUE;
} }
@ -248,10 +257,15 @@ int USB_putbyte(uint8_t byte){
if(!CDCready) return FALSE; if(!CDCready) return FALSE;
int l = 0; int l = 0;
while((l = RB_write((ringbuffer*)&rbout, &byte, 1)) != 1){ while((l = RB_write((ringbuffer*)&rbout, &byte, 1)) != 1){
if(!CDCready) return FALSE;
IWDG->KR = IWDG_REFRESH; IWDG->KR = IWDG_REFRESH;
if(lastdsz == 0) send_next(); // need to run manually - all data sent, so no IRQ on IN if(l == 0){ // overfull
if(l < 0) continue; if(lastdsz < 0) send_next();
continue;
}
} }
// send line if got EOL
if(byte == '\n' && lastdsz < 0) send_next();
return TRUE; return TRUE;
} }