Compare commits

...

72 commits

Author SHA1 Message Date
66e917de4d Актуализированы модели CAD, добавлены потерянные версии
Co-authored-by: Vladimir Latukhin <vlatukhin@gmail.com>
2025-06-05 19:47:25 +03:00
9d3aa54272 Fix doc 2025-06-04 11:44:10 +03:00
6be663c914 Merge 2025-06-04 09:57:43 +03:00
0c51667ffc Add st-link_full.py
Fix st-link_full.py
2025-06-03 21:23:56 +03:00
05621e7150 Fix test and work with bootloader
Fix tests

Fix commit
2025-06-03 13:02:57 +03:00
e9fb2656b8 Add reset to st-link test 2025-06-02 22:38:56 +03:00
1aa732c810 add test 2025-06-02 20:02:22 +03:00
d1e918371c remove simple_foc commander and monitor 2025-05-30 17:15:34 +03:00
f1d922bd34 Fix boot 2025-05-30 15:53:15 +03:00
31528a4a5b Add offset for firmware 2025-05-29 18:57:25 +03:00
3fd612a56e rename python test file names 2025-05-29 13:45:47 +03:00
10c7da1107 update pid default parameters 2025-05-29 13:45:28 +03:00
5fa3db6e6c PID CAN setup fix 2025-05-27 16:33:02 +03:00
013768ad1c Add PID test 2025-05-27 15:54:04 +03:00
d654443621 Fix cpp file 2025-05-26 22:40:53 +03:00
d2d8f89eb3 Add test 2025-05-23 09:16:41 +03:00
456b4a8b70 Fix bootloader 2025-05-23 09:12:06 +03:00
c0c42339f1 Add bootloader flag in the flash 2025-05-23 09:10:51 +03:00
ec086e2d47 Fix include and add/fixed python test 2025-05-22 18:12:54 +03:00
6844ca9a8d Add bootloader 2025-05-22 18:03:43 +03:00
4f42094b0e Divide code 2025-05-16 21:06:31 +03:00
320eb21de8 Add write pid_p coefficient on FLASH 2025-05-16 14:41:31 +03:00
2a173b836b Fix test CRC 2025-05-16 14:04:21 +03:00
0980243848 Add py test and fix work with float in FLASH 2025-05-15 23:13:07 +03:00
a0800410e0 Update struct and working for FLASH 2025-05-15 17:38:59 +03:00
2e88044e07 Fix angle 2025-05-14 20:06:19 +03:00
3e35fd99a1 For all types 2025-05-14 19:26:10 +03:00
fca10d4140 Fix CRC from read data 2025-05-13 19:05:54 +03:00
1122c97008 Fix CRC 2025-05-13 18:55:55 +03:00
7f29caeb76 Test for angle 2025-05-13 14:43:45 +03:00
ee8b011098 Add to .gitignore rar file 2025-05-13 01:01:23 +03:00
2c1fe86b58 Add to .gitignore rar file 2025-05-13 00:59:08 +03:00
de2534a890 Fix test 2025-05-12 16:37:21 +03:00
ede8525164 Add write param for test 2025-05-12 16:24:12 +03:00
ef911e5cb3 Add write param for test 2025-05-12 16:23:17 +03:00
8ecb1aca43 Fix current address 2025-05-05 14:53:37 +03:00
b36103201c Add flag for CAN 2025-05-04 22:53:42 +03:00
a2f1c2557a translate comment 2025-04-18 12:50:07 +03:00
d935263742 ADD persistent parameters (PID, ID), request-response model via CAN bus, Position Control 2025-04-17 17:45:23 +03:00
7ef7228b31 add pid 2025-04-17 16:55:48 +03:00
e65857ca6f Added PID 2025-04-17 16:49:39 +03:00
06aae3981e fix work with float type of angle 2025-04-17 15:53:03 +03:00
317a4c48ea Add setup for angle using SimpleFOC 2025-04-17 14:30:22 +03:00
9c9b182705 Added function for send data 2025-04-17 11:10:56 +03:00
c02006698e Ready for work 2025-04-16 23:09:59 +03:00
7b1b5831a4 Add new china motors 2025-03-18 20:56:45 +03:00
9539900322 Return kiplot config to root dir 2025-02-27 16:13:43 +03:00
7af6b04366 Add 2 motor versions & test stand 2025-02-27 16:01:14 +03:00
365124fd91 fix cpplint errors
fix cpplint again
2025-02-17 19:06:28 +03:00
sosiskovich
631cadca26 New PID coefficients; remove legacy 2025-02-12 21:57:27 +08:00
8525854579 Refactor ROS2 actuator with improved CAN handling and logging
- Introduced `rclcpp::Logger` for consistent logging throughout `RbsServoActuator`.
- Renamed joint state and command variables to `hw_joint_angle`, `hw_joint_velocity`, `hw_joint_target_angle`, and `hw_joint_target_velocity` for clarity.
- Added parameters `can_interface` and `can_node_id`, allowing configurable CAN interface and node ID.
- Enhanced CAN initialization and error handling in `on_init` to properly retrieve interface index and bind the socket.
- Implemented structured CAN message handling:
  - Sends activation command when the actuator is enabled.
  - Reads and logs incoming CAN frames for joint state updates.
  - Ensures error handling for failed read/write operations.
- Updated URDF (`simple_robot.urdf`) to include `can_interface` and `can_node_id` parameters for hardware configuration.
2025-02-04 13:41:56 +03:00
74c5b1d12c Enhance CAN bus scripts with argparse and error handling
- Improved error handling in `python_enable_motor.py` by capturing and displaying exception details.
- Ensured proper CAN bus shutdown in `python_enable_motor.py` with a `finally` block.
- Refactored `python_send_angle.py` to accept a command-line argument for the target angle instead of looping indefinitely.
- Refactored `python_send_velocity.py` to accept a command-line argument for target speed and removed infinite loops for better usability.
- Added `send_velocity_impulses.py`, a new script to send alternating velocity impulses over the CAN bus.
2025-02-04 13:41:05 +03:00
d5f772cb6d Adjust serial monitor speed and refine motor control logic
- Changed `monitor_speed` in `platformio.ini` from `115200` to `19200` for compatibility.
- Initialized `MotorControlInputs` struct members with default values.
- Uncommented digital write operations in `doMotor` for proper execution.
- Disabled debug output and monitoring configurations for cleaner operation.
- Adjusted motor tuning parameters by commenting out specific settings.
- Changed `Serial.begin(115200)` to `Serial.begin(19200)` in `setup()` to match the new monitor speed.
- Commented out `_delay(1000)` and `current_angle` variable to remove unnecessary delays and unused code.
2025-02-04 13:40:15 +03:00
47a87711d9 Add README file with instructions for CAN communication scripts
- Added a README file containing instructions for using the Python scripts to test and interact with a CAN bus system.
- Included details on prerequisites, usage, configuration, and troubleshooting.
- Provided step-by-step guidance for running each script, including arguments and behavior.
2025-01-18 18:40:23 +03:00
51e8fac95a Add Python test scripts for CAN communication
- Created `python_can.py`:
  - Implements a CAN message receiver that processes angle, velocity, and enable/disable flags.
- Added `python_enable_motor.py`:
  - Sends enable/disable commands to the motor via CAN.
- Added `python_send_angle.py`:
  - Sends target angle commands over the CAN bus.
- Added `python_send_velocity.py`:
  - Sends target velocity commands over the CAN bus.
- Configured all scripts to use `python-can` library with `socketcan` interface for CAN communication.
2025-01-18 18:34:05 +03:00
1534b854fc Refactor and enhance motor control implementation
- Introduced `MotorControlInputs` struct to centralize motor control state.
- Renamed `sensor` to `encoder` for clarity in naming conventions.
- Added `send_velocity`, `send_angle`, and `send_motor_enabled` functions for modular CAN message handling.
- Updated `setup_foc` to enhance motor initialization with configurable parameters.
- Replaced `run_foc` with `foc_step` for improved motor control logic:
  - Dynamically switches between angle and velocity control based on inputs.
- Enhanced CAN message handling with `read_can_step` to process specific control commands.
- Adjusted current sensing and other configuration values for precision.
- Added placeholders for temperature sensor setup and handling.
2025-01-18 18:28:56 +03:00
0199c1e38f Configure clang tools and update build settings
- Added `.clang-tidy` with custom checks to enforce code style.
- Created `.clangd` with specific compile flag additions and removals.
- Updated `.gitignore` to include new cache, metadata, and configuration files.
- Updated `platformio.ini`:
  - Bumped `Simple FOC` to version 2.3.4 and `STM32_CAN` to version 1.1.2.
  - Added `gen_compile_commands.py` as an extra script.
2025-01-18 18:27:28 +03:00
328dd0e0aa Removed unnecessary fillets, surfaces, and construction elements from each part; Eliminated duplicate parts; Restructured file and folder organization. 2025-01-13 15:09:31 +00:00
dcf22ec341 Update README.md: add renders 2024-11-16 11:34:21 +03:00
43beaea626 ADD: new tool for stator fasteners assembly & rename other tools 2024-11-11 09:34:36 +00:00
f80a5add65 Added STEP for 70mm 3D-printed servo 2024-11-11 08:09:27 +00:00
cd6aa7feb5 Printed Servos Update; Added two kind of reducers 2024-09-21 11:30:00 +00:00
vanyabeat
36253b1db5 ADDED: naive control implementation from RO2 for a robot roller motor 2024-05-24 10:57:24 +00:00
vanyabeat
e876d7e56c Add sensor AS5045, new PCB 0.4.2 adoption 2024-05-08 10:05:29 +00:00
3fb5246306 Add link to motor winder repo 2024-05-03 19:31:41 +03:00
c96949857e README update, coil winder schema 2024-05-03 19:23:08 +03:00
d003ad7f8e Test tool equipment 2024-05-03 19:05:41 +03:00
5a03517d41 Stator coils in schematics 2024-05-03 19:05:22 +03:00
e127cbf05e Old servo removed 2024-05-03 18:48:18 +03:00
fa328e1e2c Additional magnetic conductor parts 2024-04-26 10:58:42 +03:00
8e2d2dac3b zip for package archive 2024-04-08 11:50:30 +00:00
effb5a33b1 Fabrication Release Archive: tar.gz -> zip 2024-04-08 10:49:44 +00:00
365 changed files with 1283684 additions and 1023 deletions

10
.gitignore vendored
View file

@ -1,5 +1,6 @@
~$*.SLDPRT
~$*.SLDASM
*.STL
# For PCBs designed using KiCad: http://www.kicad-pcb.org/
# Format documentation: http://kicad-pcb.org/help/file-formats/
@ -29,4 +30,11 @@ fp-info-cache
# Autorouter files (exported from Pcbnew)
*.dsn
*.ses
*.ses
# Visual Studio Code
*.vscode/
# Platformio .pio
.pio/
# JetBrains CLion
.idea/

View file

@ -9,11 +9,11 @@ build_firmware:
image: python:3.9
rules:
- changes:
- "firmware/*"
- "controller/fw/*"
- ".gitlab-ci.yml"
when: on_success
before_script:
- cd firmware
- cd controller/fw/embed
- pip install -U platformio
- pio update
script:
@ -21,10 +21,25 @@ build_firmware:
- pio run
artifacts:
paths:
- firmware/.pio/build/robotroller_reborn/firmware.elf
- firmware/.pio/build/robotroller_reborn/firmware.bin
- controller/fw/embed/.pio/build/robotroller_reborn/firmware.elf
- controller/fw/embed/.pio/build/robotroller_reborn/firmware.bin
expire_in: 1 week
lint_firmware:
stage: gen_fabrication_files
image: python:3.9
rules:
- changes:
- "controller/fw/*"
- ".gitlab-ci.yml"
when: on_success
before_script:
- cd controller/fw/embed/
- pip install cpplint
script:
- pwd
- cpplint --extensions=h,hpp,cpp --recursive --linelength=120 --filter=-build/include_subdir,-legal/copyright --output=vs7 src include test lib
### Gitlab CI/CD example for KiCad
# workflow:
@ -45,7 +60,7 @@ clone:
stage: gen_fabrication_files
trigger:
include:
- remote: 'https://gitlab.com/robossembler/roboarm-diy-version/-/raw/f763e3ee6c516aefee3651e369b5000ed4c90d94/.kicad-pipeline.yml'
- remote: 'https://gitlab.com/robossembler/roboarm-diy-version/-/raw/a200bcad9708b65b51f54da9ed426d2233308b84/.kicad-pipeline.yml'
strategy: depend
rules: !reference [.default_rules, rules]
@ -62,6 +77,6 @@ clone:
Robotroller-PCB:
variables:
PACKAGE_NAME: 'Robotroller-PCB'
FOLDER: 'brd'
FOLDER: 'controller/hw'
PROJECT_NAME: 'motor_controller_50mm'
extends: .kicad-pipeline

View file

@ -4,12 +4,31 @@ All notable changes to this project will be documented in this file.
The format is based on [Keep a Changelog](http://keepachangelog.com/)
and this project adheres to [Semantic Versioning](http://semver.org/).
## [Unreleased] - yyyy-mm-dd
## [0.1.0] 70mm Servo - 2024-06-19
Изменения в конструкции 70 мм. двигателей
### Added
Добавлены модификации двигателей для металлического магнитопровода
1. на 2 элементах статора добавены лучи, препятствующие перетиранию провода о металл сердечника
2. Поправлены размер фиксатора крышки мотора статора.
### Changed
Ротор 70 мм
1. Изменены размеры отверстий под установку магнитов
2. Изменён крепеж вала ротора к подшипнику
3. Увеличены вентиляционные лопатки
4. Увеличен диаметр отверстия для установки магнита датчика угла
5. Изменена верхняя крышка для улучшения процесса печати
6. Уменьшены фиксирующие магниты пластины для уменьшения вероятности трения ротора о статор
7. Увеличена толщина стенок для получения более жесткой конструкции
Статор 70 мм
1. Изменена форма щёчек катушек для улучшения процесса печати
2. Добавлено отверстие для крепления провода (концов звезды в соответствующей схеме подключения)
### Fixed
## [0.4.0] PCB Controller - 2024-03-24

View file

@ -1,24 +1,71 @@
# Сервопривод Робосборщика
![servo printed images](img/title-bar-rbs-servo.png)
![servo printed images](img/robossembler-servo-reducer-exploding-view-01.jpg)
![servo printed images](img/robossembler-servo-reducer-exploding-view-02.jpg)
Бесщёточный сервопривод постоянного тока, адаптированный для автоматического производства. Разработан для управления 6-осевым роботом-манипулятором Robossembler Arm, но может использоваться и как самостоятельное изделие в составе других систем.
Сервопривод на базе бесщёточного двигателя постоянного тока, адаптированный для производства с помощью 3D-печати. Разработан для управления 6-осевым роботом-манипулятором [Robossembler Arm](https://gitlab.com/robossembler/roboarm-diy-version), но может использоваться и как самостоятельное изделие в составе других систем. Предусматривается две конструкции статора двигателя: один для изготовления с помощью 3D-печати, другой с помощью листовой электротехнеской стали, нарезаемой на лазерном станке.
Ключевые особенности:
Ключевые особенности:
- Высокая мощность (допустимость редуктора)
- Высокая скорость (компенсация наличия редуктора)
- Хорошая динамика (разгон-торможение)
- Возможность электрического тормоза
В состав репозитория включены модели редукторов двух типов для использования в составе сервопривода. Исходные файлы редукторов представлены в директории `src/REDUCTOR`. В настоящее время основным является прециссирующий редуктор с соотношением 1:43.
Для управления используется универсальная плата-контроллер, которая может быть использована в вариантах исполнения двигателей разных диаметров (на данный момент 50 мм и 70 мм) со сходными характеристиками обмоток. Контроллер управляется через CAN-интерфейс.
## Внешний вид
![](img/servo-reducer-assembled.jpg)
## Описание директорий
- `brd` - KiCAD проект печатной платы контроллера.
- `src` - 3D-модели вариантов исполнения мотора: 50 мм, 70 мм, металлическая версия двигателя (не интегрирована с контроллером).
```[servo]
├── controller/ # Плата контроллер
│ ├── fw/ # Исходный код прошивки микроконтроллера
│ │ ├── embed/ # Инструкция по сборке и загрузке прошивки
│ │ └── test/ # Тесты для проверки встроенного ПО
│ └── hw/ # Проект печатной платы контроллера в kicad
├── img/ # Изображения для README.md
├── motor/ # Все файлы сборок и деталей моторов в формате Solidworks
├── reducer/ # Проекты редукторов в формате Solidworks
├── ros2_environment/ # Пакеты для управления мотором из ROS 2 с помощью ros2_control
└── tools/ # Вспомогательное оборудование для тестирования, испытаний
├── conductor-for-fasteners-70mm/ # Проект оснастки для вкручивания винтов в пластиковый статор 72мм мотора
├── test-reductor-stend/ # Стенд для испытания редуктора
└── torque-test-stend/ # Стенд для измерения усилия сервопривода
```
## Краткая инструкция по изготовлению
### Статор
Для удобства изготовления статоров разработан станок для намотки катушек индуктивности. Исходные файлы для производства станка и инструкции размещены в репозитории [gitlab.com/robossembler/cnc/motor-wire-winder](https://gitlab.com/robossembler/cnc/motor-wire-winder).
### Сборка
1. Вставить 28 магнитов в ротор
2. Установить подшипник в статор
3. Установить проставку в статор между подшипником и платой
4. Припаять плату к обмоткам (схема обмоток приведена ниже) и установить ее в статор
5. Накрыть плату крышкой
6. Установить фиксирующий шплинт
7. Надеть на сборку статора ротор
8. Подключить разъем программирования XP3 и прошить с помощью ST-Link-совместимого программатора
## Фото прототипов
Первый прототип изготовленного печатного мотора диаметром 50мм.
![servo printed](img/first-prototype-rbs-servo-50mm.png)
![servo printed](img/first-prototype-rbs-servo-50mm.png)
Современная версия привода диаметром 70мм.
![](img/70mm-prototype-02-inside.jpg)
## Схемы намотки
| Двигатель 70мм | Двигатель 50мм |
| ----------- | ----------- |
| ![coil winder schema](img/coil_winder_schema.jpg) | ![coil winder schema](img/coil_winder_schema_50mm.jpg) |

View file

@ -1,547 +0,0 @@
EESchema-LIBRARY Version 2.4
#encoding utf-8
#
# Amplifier_Current_INA194
#
DEF Amplifier_Current_INA194 U 0 5 Y Y 1 F N
F0 "U" 150 150 50 H V C CNN
F1 "Amplifier_Current_INA194" 150 -150 50 H V C CNN
F2 "Package_TO_SOT_SMD:SOT-23-5" 0 0 50 H I C CNN
F3 "" 0 0 50 H I C CNN
ALIAS INA194 INA195
$FPLIST
SOT?23*
$ENDFPLIST
DRAW
P 4 0 1 10 200 0 -200 200 -200 -200 200 0 f
X ~ 1 300 0 100 L 50 50 1 1 O
X GND 2 -100 -300 150 U 50 50 1 1 W
X + 3 -300 100 100 R 50 50 1 1 I
X - 4 -300 -100 100 R 50 50 1 1 I
X V+ 5 -100 300 150 D 50 50 1 1 W
ENDDRAW
ENDDEF
#
# Connector_Generic_Conn_02x05_Counter_Clockwise
#
DEF Connector_Generic_Conn_02x05_Counter_Clockwise J 0 40 Y N 1 F N
F0 "J" 50 300 50 H V C CNN
F1 "Connector_Generic_Conn_02x05_Counter_Clockwise" 50 -300 50 H V C CNN
F2 "" 0 0 50 H I C CNN
F3 "" 0 0 50 H I C CNN
$FPLIST
Connector*:*_2x??_*
$ENDFPLIST
DRAW
S -50 -195 0 -205 1 1 6 N
S -50 -95 0 -105 1 1 6 N
S -50 5 0 -5 1 1 6 N
S -50 105 0 95 1 1 6 N
S -50 205 0 195 1 1 6 N
S -50 250 150 -250 1 1 10 f
S 150 -195 100 -205 1 1 6 N
S 150 -95 100 -105 1 1 6 N
S 150 5 100 -5 1 1 6 N
S 150 105 100 95 1 1 6 N
S 150 205 100 195 1 1 6 N
X Pin_1 1 -200 200 150 R 50 50 1 1 P
X Pin_10 10 300 200 150 L 50 50 1 1 P
X Pin_2 2 -200 100 150 R 50 50 1 1 P
X Pin_3 3 -200 0 150 R 50 50 1 1 P
X Pin_4 4 -200 -100 150 R 50 50 1 1 P
X Pin_5 5 -200 -200 150 R 50 50 1 1 P
X Pin_6 6 300 -200 150 L 50 50 1 1 P
X Pin_7 7 300 -100 150 L 50 50 1 1 P
X Pin_8 8 300 0 150 L 50 50 1 1 P
X Pin_9 9 300 100 150 L 50 50 1 1 P
ENDDRAW
ENDDEF
#
# Connector_Generic_Conn_02x08_Odd_Even
#
DEF Connector_Generic_Conn_02x08_Odd_Even J 0 40 Y N 1 F N
F0 "J" 50 400 50 H V C CNN
F1 "Connector_Generic_Conn_02x08_Odd_Even" 50 -500 50 H V C CNN
F2 "" 0 0 50 H I C CNN
F3 "" 0 0 50 H I C CNN
$FPLIST
Connector*:*_2x??_*
$ENDFPLIST
DRAW
S -50 -395 0 -405 1 1 6 N
S -50 -295 0 -305 1 1 6 N
S -50 -195 0 -205 1 1 6 N
S -50 -95 0 -105 1 1 6 N
S -50 5 0 -5 1 1 6 N
S -50 105 0 95 1 1 6 N
S -50 205 0 195 1 1 6 N
S -50 305 0 295 1 1 6 N
S -50 350 150 -450 1 1 10 f
S 150 -395 100 -405 1 1 6 N
S 150 -295 100 -305 1 1 6 N
S 150 -195 100 -205 1 1 6 N
S 150 -95 100 -105 1 1 6 N
S 150 5 100 -5 1 1 6 N
S 150 105 100 95 1 1 6 N
S 150 205 100 195 1 1 6 N
S 150 305 100 295 1 1 6 N
X Pin_1 1 -200 300 150 R 50 50 1 1 P
X Pin_10 10 300 -100 150 L 50 50 1 1 P
X Pin_11 11 -200 -200 150 R 50 50 1 1 P
X Pin_12 12 300 -200 150 L 50 50 1 1 P
X Pin_13 13 -200 -300 150 R 50 50 1 1 P
X Pin_14 14 300 -300 150 L 50 50 1 1 P
X Pin_15 15 -200 -400 150 R 50 50 1 1 P
X Pin_16 16 300 -400 150 L 50 50 1 1 P
X Pin_2 2 300 300 150 L 50 50 1 1 P
X Pin_3 3 -200 200 150 R 50 50 1 1 P
X Pin_4 4 300 200 150 L 50 50 1 1 P
X Pin_5 5 -200 100 150 R 50 50 1 1 P
X Pin_6 6 300 100 150 L 50 50 1 1 P
X Pin_7 7 -200 0 150 R 50 50 1 1 P
X Pin_8 8 300 0 150 L 50 50 1 1 P
X Pin_9 9 -200 -100 150 R 50 50 1 1 P
ENDDRAW
ENDDEF
#
# Device_C
#
DEF Device_C C 0 10 N Y 1 F N
F0 "C" 25 100 50 H V L CNN
F1 "Device_C" 25 -100 50 H V L CNN
F2 "" 38 -150 50 H I C CNN
F3 "" 0 0 50 H I C CNN
$FPLIST
C_*
$ENDFPLIST
DRAW
P 2 0 1 20 -80 -30 80 -30 N
P 2 0 1 20 -80 30 80 30 N
X ~ 1 0 150 110 D 50 50 1 1 P
X ~ 2 0 -150 110 U 50 50 1 1 P
ENDDRAW
ENDDEF
#
# Device_C_Small
#
DEF Device_C_Small C 0 10 N N 1 F N
F0 "C" 10 70 50 H V L CNN
F1 "Device_C_Small" 10 -80 50 H V L CNN
F2 "" 0 0 50 H I C CNN
F3 "" 0 0 50 H I C CNN
$FPLIST
C_*
$ENDFPLIST
DRAW
P 2 0 1 13 -60 -20 60 -20 N
P 2 0 1 12 -60 20 60 20 N
X ~ 1 0 100 80 D 50 50 1 1 P
X ~ 2 0 -100 80 U 50 50 1 1 P
ENDDRAW
ENDDEF
#
# Device_L
#
DEF Device_L L 0 40 N N 1 F N
F0 "L" -50 0 50 V V C CNN
F1 "Device_L" 75 0 50 V V C CNN
F2 "" 0 0 50 H I C CNN
F3 "" 0 0 50 H I C CNN
$FPLIST
Choke_*
*Coil*
Inductor_*
L_*
$ENDFPLIST
DRAW
A 0 -75 25 -899 899 0 1 0 N 0 -100 0 -50
A 0 -25 25 -899 899 0 1 0 N 0 -50 0 0
A 0 25 25 -899 899 0 1 0 N 0 0 0 50
A 0 75 25 -899 899 0 1 0 N 0 50 0 100
X 1 1 0 150 50 D 50 50 1 1 P
X 2 2 0 -150 50 U 50 50 1 1 P
ENDDRAW
ENDDEF
#
# Device_LED
#
DEF Device_LED D 0 40 N N 1 F N
F0 "D" 0 100 50 H V C CNN
F1 "Device_LED" 0 -100 50 H V C CNN
F2 "" 0 0 50 H I C CNN
F3 "" 0 0 50 H I C CNN
$FPLIST
LED*
LED_SMD:*
LED_THT:*
$ENDFPLIST
DRAW
P 2 0 1 10 -50 -50 -50 50 N
P 2 0 1 0 -50 0 50 0 N
P 4 0 1 10 50 -50 50 50 -50 0 50 -50 N
P 5 0 1 0 -120 -30 -180 -90 -150 -90 -180 -90 -180 -60 N
P 5 0 1 0 -70 -30 -130 -90 -100 -90 -130 -90 -130 -60 N
X K 1 -150 0 100 R 50 50 1 1 P
X A 2 150 0 100 L 50 50 1 1 P
ENDDRAW
ENDDEF
#
# Device_R
#
DEF Device_R R 0 0 N Y 1 F N
F0 "R" 80 0 50 V V C CNN
F1 "Device_R" 0 0 50 V V C CNN
F2 "" -70 0 50 V I C CNN
F3 "" 0 0 50 H I C CNN
$FPLIST
R_*
$ENDFPLIST
DRAW
S -40 -100 40 100 0 1 10 N
X ~ 1 0 150 50 D 50 50 1 1 P
X ~ 2 0 -150 50 U 50 50 1 1 P
ENDDRAW
ENDDEF
#
# Device_Thermistor_NTC
#
DEF Device_Thermistor_NTC TH 0 0 N Y 1 F N
F0 "TH" -175 0 50 V V C CNN
F1 "Device_Thermistor_NTC" 125 0 50 V V C CNN
F2 "" 0 50 50 H I C CNN
F3 "" 0 50 50 H I C CNN
$FPLIST
*NTC*
*Thermistor*
PIN?ARRAY*
bornier*
*Terminal?Block*
R_*
$ENDFPLIST
DRAW
A -126 88 7 -265 818 0 1 0 N -120 85 -125 95
A -110 85 10 1800 -900 0 1 0 N -120 85 -110 75
A -110 85 10 -900 0 0 1 0 N -110 75 -100 85
A -110 110 10 0 900 0 1 0 N -100 110 -110 120
A -110 110 10 900 1800 0 1 0 N -110 120 -120 110
A -110 110 10 1800 -900 0 1 0 N -120 110 -110 100
A -104 119 20 -1075 -253 0 1 0 N -110 100 -85 110
S -40 100 40 -100 0 1 10 N
P 2 0 1 0 -100 85 -100 110 N
P 4 0 1 0 -70 100 -70 60 70 -60 70 -100 N
P 6 0 1 0 -100 -145 -100 -55 -110 -85 -90 -85 -100 -55 -100 -65 F
P 6 0 1 0 -70 -55 -70 -145 -80 -115 -60 -115 -70 -145 -70 -135 F
X ~ 1 0 150 50 D 50 50 1 1 P
X ~ 2 0 -150 50 U 50 50 1 1 P
ENDDRAW
ENDDEF
#
# Diode_1N5818
#
DEF Diode_1N5818 D 0 40 N N 1 F N
F0 "D" 0 100 50 H V C CNN
F1 "Diode_1N5818" 0 -100 50 H V C CNN
F2 "Diode_THT:D_DO-41_SOD81_P10.16mm_Horizontal" 0 -175 50 H I C CNN
F3 "" 0 0 50 H I C CNN
ALIAS SB130 SB140 SB150 SB160 1N5817 1N5818 1N5819
$FPLIST
D*DO?41*
$ENDFPLIST
DRAW
P 2 0 1 0 50 0 -50 0 N
P 4 0 1 10 50 50 50 -50 -50 0 50 50 N
P 6 0 1 10 -75 25 -75 50 -50 50 -50 -50 -25 -50 -25 -25 N
X K 1 -150 0 100 R 50 50 1 1 P
X A 2 150 0 100 L 50 50 1 1 P
ENDDRAW
ENDDEF
#
# Driver_Motor_drv8313
#
DEF Driver_Motor_drv8313 U 0 40 Y Y 1 F N
F0 "U" -300 50 50 H V C CNN
F1 "Driver_Motor_drv8313" 200 50 50 H V C CNN
F2 "" -700 0 50 H I C CNN
F3 "" -700 0 50 H I C CNN
DRAW
S -450 -50 350 -1550 0 1 0 f
X cpl 1 -550 -150 100 R 50 50 1 1 I
X pgnd3 10 -550 -1050 100 R 50 50 1 1 I
X vm 11 -550 -1150 100 R 50 50 1 1 I
X compp 12 -550 -1250 100 R 50 50 1 1 I
X compn 13 -550 -1350 100 R 50 50 1 1 I
X gnd 14 -550 -1450 100 R 50 50 1 1 W
X v3p3 15 450 -1450 100 L 50 50 1 1 w
X nReset 16 450 -1350 100 L 50 50 1 1 I
X nSleep 17 450 -1250 100 L 50 50 1 1 I
X nFault 18 450 -1150 100 L 50 50 1 1 O
X nCompo 19 450 -1050 100 L 50 50 1 1 I
X cph 2 -550 -250 100 R 50 50 1 1 I
X gnd 20 450 -950 100 L 50 50 1 1 W
X nc 21 450 -850 100 L 50 50 1 1 I
X en3 22 450 -750 100 L 50 50 1 1 I
X in3 23 450 -650 100 L 50 50 1 1 I
X en2 24 450 -550 100 L 50 50 1 1 I
X in2 25 450 -450 100 L 50 50 1 1 I
X en1 26 450 -350 100 L 50 50 1 1 I
X in1 27 450 -250 100 L 50 50 1 1 I
X gnd 28 450 -150 100 L 50 50 1 1 W
X vcp 3 -550 -350 100 R 50 50 1 1 I
X vm 4 -550 -450 100 R 50 50 1 1 I
X out1 5 -550 -550 100 R 50 50 1 1 O
X pgnd1 6 -550 -650 100 R 50 50 1 1 I
X pgnd2 7 -550 -750 100 R 50 50 1 1 I
X out2 8 -550 -850 100 R 50 50 1 1 O
X out3 9 -550 -950 100 R 50 50 1 1 O
ENDDRAW
ENDDEF
#
# Interface_CAN_LIN_SN65HVD235
#
DEF Interface_CAN_LIN_SN65HVD235 U 0 40 Y Y 1 F N
F0 "U" -100 400 50 H V R CNN
F1 "Interface_CAN_LIN_SN65HVD235" -100 300 50 H V R CNN
F2 "Package_SO:SOIC-8_3.9x4.9mm_P1.27mm" 0 -500 50 H I C CNN
F3 "" -100 400 50 H I C CNN
$FPLIST
SOIC*3.9x4.9mm*P1.27mm*
$ENDFPLIST
DRAW
S -300 200 300 -300 0 1 10 f
X D 1 -400 100 100 R 50 50 1 1 I
X GND 2 0 -400 100 U 50 50 1 1 W
X VCC 3 0 300 100 D 50 50 1 1 W
X R 4 -400 0 100 R 50 50 1 1 O
X AB 5 -400 -100 100 R 50 50 1 1 I
X CANL 6 400 -100 100 L 50 50 1 1 B
X CANH 7 400 0 100 L 50 50 1 1 B
X Rs 8 -400 -200 100 R 50 50 1 1 I
ENDDRAW
ENDDEF
#
# MCU_ST_STM32F4_STM32F446RETx
#
DEF MCU_ST_STM32F4_STM32F446RETx U 0 20 Y Y 1 F N
F0 "U" -600 1650 50 H V L CNN
F1 "MCU_ST_STM32F4_STM32F446RETx" 400 1650 50 H V L CNN
F2 "Package_QFP:LQFP-64_10x10mm_P0.5mm" -600 -1700 50 H I R CNN
F3 "" 0 0 50 H I C CNN
ALIAS STM32F446RETx
$FPLIST
LQFP*10x10mm*P0.5mm*
$ENDFPLIST
DRAW
S -600 -1700 600 1600 0 1 10 f
X VBAT 1 -200 1700 100 D 50 50 1 1 W
X PC2 10 -700 -300 100 R 50 50 1 1 B
X PC3 11 -700 -400 100 R 50 50 1 1 B
X VSSA 12 200 -1800 100 U 50 50 1 1 W
X VDDA 13 300 1700 100 D 50 50 1 1 W
X PA0 14 700 1500 100 L 50 50 1 1 B
X PA1 15 700 1400 100 L 50 50 1 1 B
X PA2 16 700 1300 100 L 50 50 1 1 B
X PA3 17 700 1200 100 L 50 50 1 1 B
X VSS 18 -200 -1800 100 U 50 50 1 1 W
X VDD 19 -100 1700 100 D 50 50 1 1 W
X PC13 2 -700 -1400 100 R 50 50 1 1 B
X PA4 20 700 1100 100 L 50 50 1 1 B
X PA5 21 700 1000 100 L 50 50 1 1 B
X PA6 22 700 900 100 L 50 50 1 1 B
X PA7 23 700 800 100 L 50 50 1 1 B
X PC4 24 -700 -500 100 R 50 50 1 1 B
X PC5 25 -700 -600 100 R 50 50 1 1 B
X PB0 26 700 -200 100 L 50 50 1 1 B
X PB1 27 700 -300 100 L 50 50 1 1 B
X PB2 28 700 -400 100 L 50 50 1 1 B
X PB10 29 700 -1200 100 L 50 50 1 1 B
X PC14 3 -700 -1500 100 R 50 50 1 1 B
X VCAP_1 30 -700 1100 100 R 50 50 1 1 W
X VSS 31 -100 -1800 100 U 50 50 1 1 W
X VDD 32 0 1700 100 D 50 50 1 1 W
X PB12 33 700 -1300 100 L 50 50 1 1 B
X PB13 34 700 -1400 100 L 50 50 1 1 B
X PB14 35 700 -1500 100 L 50 50 1 1 B
X PB15 36 700 -1600 100 L 50 50 1 1 B
X PC6 37 -700 -700 100 R 50 50 1 1 B
X PC7 38 -700 -800 100 R 50 50 1 1 B
X PC8 39 -700 -900 100 R 50 50 1 1 B
X PC15 4 -700 -1600 100 R 50 50 1 1 B
X PC9 40 -700 -1000 100 R 50 50 1 1 B
X PA8 41 700 700 100 L 50 50 1 1 B
X PA9 42 700 600 100 L 50 50 1 1 B
X PA10 43 700 500 100 L 50 50 1 1 B
X PA11 44 700 400 100 L 50 50 1 1 B
X PA12 45 700 300 100 L 50 50 1 1 B
X PA13 46 700 200 100 L 50 50 1 1 B
X VSS 47 0 -1800 100 U 50 50 1 1 W
X VDD 48 100 1700 100 D 50 50 1 1 W
X PA14 49 700 100 100 L 50 50 1 1 B
X PH0 5 -700 400 100 R 50 50 1 1 I
X PA15 50 700 0 100 L 50 50 1 1 B
X PC10 51 -700 -1100 100 R 50 50 1 1 B
X PC11 52 -700 -1200 100 R 50 50 1 1 B
X PC12 53 -700 -1300 100 R 50 50 1 1 B
X PD2 54 -700 100 100 R 50 50 1 1 B
X PB3 55 700 -500 100 L 50 50 1 1 B
X PB4 56 700 -600 100 L 50 50 1 1 B
X PB5 57 700 -700 100 L 50 50 1 1 B
X PB6 58 700 -800 100 L 50 50 1 1 B
X PB7 59 700 -900 100 L 50 50 1 1 B
X PH1 6 -700 300 100 R 50 50 1 1 I
X BOOT0 60 -700 1300 100 R 50 50 1 1 I
X PB8 61 700 -1000 100 L 50 50 1 1 B
X PB9 62 700 -1100 100 L 50 50 1 1 B
X VSS 63 100 -1800 100 U 50 50 1 1 W
X VDD 64 200 1700 100 D 50 50 1 1 W
X NRST 7 -700 1500 100 R 50 50 1 1 I
X PC0 8 -700 -100 100 R 50 50 1 1 B
X PC1 9 -700 -200 100 R 50 50 1 1 B
ENDDRAW
ENDDEF
#
# Mechanical_MountingHole_Pad
#
DEF Mechanical_MountingHole_Pad H 0 40 N N 1 F N
F0 "H" 0 250 50 H V C CNN
F1 "Mechanical_MountingHole_Pad" 0 175 50 H V C CNN
F2 "" 0 0 50 H I C CNN
F3 "" 0 0 50 H I C CNN
$FPLIST
MountingHole*Pad*
$ENDFPLIST
DRAW
C 0 50 50 0 1 50 N
X 1 1 0 -100 100 U 50 50 1 1 I
ENDDRAW
ENDDEF
#
# Regulator_Switching_LM2594HVM-3.3
#
DEF Regulator_Switching_LM2594HVM-3.3 U 0 20 Y Y 1 F N
F0 "U" -300 250 50 H V L CNN
F1 "Regulator_Switching_LM2594HVM-3.3" 0 250 50 H V L CNN
F2 "Package_SO:SOIC-8_3.9x4.9mm_P1.27mm" 200 -250 50 H I L CIN
F3 "" 0 100 50 H I C CNN
ALIAS LM2594M-5.0 LM2594M-12 LM2594M-ADJ LM2594HVM-3.3 LM2594HVM-5.0 LM2594HVM-12 LM2594HVM-ADJ
$FPLIST
SOIC*3.9x4.9mm*
$ENDFPLIST
DRAW
S -300 200 300 -200 0 1 10 f
X NC 1 -200 -300 100 U 50 50 1 1 P
X NC 2 -100 -300 100 U 50 50 1 1 P
X NC 3 0 -300 100 U 50 50 1 1 P
X FB 4 400 100 100 L 50 50 1 1 I
X ~ON~/OFF 5 -400 0 100 R 50 50 1 1 I
X GND 6 200 -300 100 U 50 50 1 1 W
X VIN 7 -400 100 100 R 50 50 1 1 W
X OUT 8 400 0 100 L 50 50 1 1 O
ENDDRAW
ENDDEF
#
# Sensor_Magnetic_AS5045B
#
DEF Sensor_Magnetic_AS5045B U 0 20 Y Y 1 F N
F0 "U" -400 450 50 H V L CNN
F1 "Sensor_Magnetic_AS5045B" 450 450 50 H V R CNN
F2 "Package_SO:SSOP-16_5.3x6.2mm_P0.65mm" 150 -450 50 H I L CNN
F3 "" -2150 1600 50 H I C CNN
$FPLIST
SSOP*5.3x6.2mm*P0.65mm*
$ENDFPLIST
DRAW
A 0 0 110 -1799 -1 0 1 10 N -110 0 110 0
C 0 0 80 0 1 10 N
S -400 400 400 -400 0 1 10 f
P 2 0 1 10 -110 0 -130 -20 N
P 2 0 1 10 -110 0 -90 -20 N
P 2 0 1 10 110 0 90 -20 N
P 2 0 1 10 110 0 130 -20 N
P 4 0 1 0 10 10 50 -30 30 -50 -10 -10 N
P 7 0 1 0 -30 50 10 10 -10 -10 -50 30 -40 40 -30 50 -25 45 F
X MagINCn 1 -500 -200 100 R 50 50 1 1 C
X CLK 10 500 100 100 L 50 50 1 1 I
X CSn 11 500 0 100 L 50 50 1 1 I
X PWM 12 500 -300 100 L 50 50 1 1 O
X NC 13 400 -200 100 L 50 50 1 1 N N
X NC 14 100 -400 100 U 50 50 1 1 N N
X VDD3V3 15 -100 500 100 D 50 50 1 1 W
X VDD5V 16 0 500 100 D 50 50 1 1 W
X MagDECn 2 -500 -300 100 R 50 50 1 1 C
X A 3 -500 300 100 R 50 50 1 1 O
X B 4 -500 200 100 R 50 50 1 1 O
X NC 5 400 -100 100 L 50 50 1 1 N N
X I 6 -500 100 100 R 50 50 1 1 O
X VSS 7 0 -500 100 U 50 50 1 1 W
X PDIO 8 500 300 100 L 50 50 1 1 I
X DO 9 500 200 100 L 50 50 1 1 O
ENDDRAW
ENDDEF
#
# kicad_Library_PROGRAMMATOR
#
DEF kicad_Library_PROGRAMMATOR xp 0 40 Y Y 1 F N
F0 "xp" -350 900 50 H V C CNN
F1 "kicad_Library_PROGRAMMATOR" -400 200 50 H V C CNN
F2 "Connector_IDC:IDC-Header_2x05_P2.54mm_Vertical" -350 900 50 H I C CNN
F3 "" -350 900 50 H I C CNN
DRAW
S -700 800 50 300 0 1 0 f
X GND 1 -800 750 100 R 50 50 1 1 P
X +5V 10 150 350 100 L 50 50 1 1 w
X +3V 2 150 750 100 L 50 50 1 1 w
X RESET 3 -800 650 100 R 50 50 1 1 I
X BOOT 4 150 650 100 L 50 50 1 1 I
X RX 5 -800 550 100 R 50 50 1 1 I
X TX 6 150 550 100 L 50 50 1 1 O
X SWDCLK 7 -800 450 100 R 50 50 1 1 I
X SWDDTA 8 150 450 100 L 50 50 1 1 B
X GND 9 -800 350 100 R 50 50 1 1 P
ENDDRAW
ENDDEF
#
# power_+24V
#
DEF power_+24V #PWR 0 0 Y Y 1 F P
F0 "#PWR" 0 -150 50 H I C CNN
F1 "power_+24V" 0 140 50 H V C CNN
F2 "" 0 0 50 H I C CNN
F3 "" 0 0 50 H I C CNN
DRAW
P 2 0 1 0 -30 50 0 100 N
P 2 0 1 0 0 0 0 100 N
P 2 0 1 0 0 100 30 50 N
X +24V 1 0 0 0 U 50 50 1 1 W N
ENDDRAW
ENDDEF
#
# power_+3.3V
#
DEF power_+3.3V #PWR 0 0 Y Y 1 F P
F0 "#PWR" 0 -150 50 H I C CNN
F1 "power_+3.3V" 0 140 50 H V C CNN
F2 "" 0 0 50 H I C CNN
F3 "" 0 0 50 H I C CNN
ALIAS +3.3V
DRAW
P 2 0 1 0 -30 50 0 100 N
P 2 0 1 0 0 0 0 100 N
P 2 0 1 0 0 100 30 50 N
X +3V3 1 0 0 0 U 50 50 1 1 W N
ENDDRAW
ENDDEF
#
# power_GND
#
DEF power_GND #PWR 0 0 Y Y 1 F P
F0 "#PWR" 0 -250 50 H I C CNN
F1 "power_GND" 0 -150 50 H V C CNN
F2 "" 0 0 50 H I C CNN
F3 "" 0 0 50 H I C CNN
DRAW
P 6 0 1 0 0 0 0 -50 50 -50 0 -100 -50 -50 0 -50 N
X GND 1 0 0 0 D 50 50 1 1 W N
ENDDRAW
ENDDEF
#
#End Library

68
controller/fw/README.md Normal file
View file

@ -0,0 +1,68 @@
# Встроенное ПО для сервопривода на STM32F446RE
## Для разработки
- [Установить platformio](#introduction)
```bash
pip install -U platformio
```
- Установить python3
```bash
sudo apt install python3
```
- Устаноивть st-link
```bash
sudo apt install st-link
```
### Прошивка делится на два файла один для загрузчика другой для основной прошивки. Чтобы загрузить как описано ниже нужно находится в директории этого проекта. Нужно сделать как для bootloader так и для embed
- [Скомпилировать проект](#build_project)
```bash
platformio run --environment robotroller_reborn
```
- [Загрузить прошивку](#upload_project)
```bash
platformio run --target upload --environment robotroller_reborn
```
## Другой способ прошивки
## Выбор интерфейса прошивки
### Для основной прошивки в директории ./embed
- Если уже есть какя-то основная прошивка, то чтобы перепрошить другую прошивку, добавляем флаг для бутлоадера
```bash
python3 firmw_update_flag.py [адрес устройства]
```
- Передача прошивки по CAN
```bash
python3 firmware_can.py firmware.hex [адрес устройства]
```
### St-link(нет адресации можно прошивать только по одному)
```bash
python3 st-link.py firmware.hex
```
### St-link_full(полная прошивка без адресации)
#### Прошивает и программатор и основную прошивку можно находится как в ./embed, так и в ./bootloader(в директории где есть данный тест в папке test).
- Если до этого сохраняли адреса и данные, то они останутся даже при полной перепрошивке
- Если бутлоадер не был прошит и FLASH микрокотроллера полностью стерта
- [Скачать прошивку и бутлоадер в hex формате]
ССЫЛКА
- [Прошить через программатор]
```bash
python3 st-link_full.py bootloader.hex firmware.hex
```
## Работа по CAN
#### Для основной прошивки в директории ./embed
- Установка адреса(если до этого не был установлен адрес, то адрес устройства = 0)
```bash
python3 set_id.py [адрес устройства]
```
- Установка PID коэффициентов для угла
```bash
python3 writePID_angle_parametrs.py [адрес устройства]
```
-Чтение PID коэффициентов для угла
```bash
python3 readPID_angle_parametrs.py [адрес устройства]

View file

@ -0,0 +1 @@
Checks: '-*, -misc-definitions-in-headers'

View file

@ -0,0 +1,18 @@
CompileFlags:
Add:
[
# -mlong-calls,
-DSSIZE_MAX,
-DLWIP_NO_UNISTD_H=1,
-Dssize_t=long,
-D_SSIZE_T_DECLARED,
]
Remove:
[
-fno-tree-switch-conversion,
-mtext-section-literals,
-mlongcalls,
-fstrict-volatile-bitfields,
-free,
-fipa-pta,
]

View file

@ -3,3 +3,7 @@
.vscode/c_cpp_properties.json
.vscode/launch.json
.vscode/ipch
.cache/
.metadata/
cubemx_config/
compile_commands.json

View file

@ -0,0 +1,19 @@
Import("env")
# Получаем путь к компилятору из окружения PlatformIO
gcc_path = env.subst("$CC")
# Выполняем команду для получения версии компилятора
import subprocess
try:
result = subprocess.run([gcc_path, "--version"], stdout=subprocess.PIPE, stderr=subprocess.PIPE, text=True)
if result.returncode == 0:
print(f"GCC version: {result.stdout}")
else:
print(f"Failed to get GCC version: {result.stderr}")
except Exception as e:
print(f"Error while getting GCC version: {e}")
# Дополнительно проверяем путь к компилятору
print(f"Compiler path: {gcc_path}")

View file

@ -0,0 +1,8 @@
import os
Import("env")
# include toolchain paths
env.Replace(COMPILATIONDB_INCLUDE_TOOLCHAIN=True)
# override compilation DB path
env.Replace(COMPILATIONDB_PATH="compile_commands.json")

View file

@ -0,0 +1,11 @@
Import("env")
hex_name = "bootloader.hex"
# Custom HEX from ELF
env.AddPostAction(
"$BUILD_DIR/${PROGNAME}.elf",
env.VerboseAction(" ".join([
"$OBJCOPY", "-O", "ihex", "-R", ".eeprom",
"$BUILD_DIR/${PROGNAME}.elf", "$BUILD_DIR/{}".format(hex_name)
]), "Building $BUILD_DIR/{}".format(hex_name))
)

View file

@ -0,0 +1,86 @@
#ifndef FLASH_H_
#define FLASH_H_
#include "stm32f446xx.h"
#include <stdio.h>
#include <stdlib.h>
/* no padding for this struct, beacuse storing 8 bytes*/
typedef struct{
uint8_t data_id; // data_id = id register of can
uint8_t data_type;
uint16_t crc;
uint32_t value;
// uint32_t write_ptr_now;
}FLASH_RECORD;
enum {
addr_id = 0,
pid_p = 1,
pid_i,
pid_d,
firmw,
foc_id,
angl,
vel
};
/* for saved in FLASH float data*/
union{
uint32_t i;
float f;
}conv_float_to_int;
#define FLASH_RECORD_SIZE sizeof(FLASH_RECORD) //size flash struct
// Flash sectors for STM32F407
#define APP_ADDRESS 0x08008000
#define UPDATE_FLAG 0xDEADBEEF // flag forz update firmware
#define BOOT_CAN_ID 0x01 // CAN ID bootloader
#define BOOT_CAN_END 0x02 // CAN ID end of transfer
#define DATA_CAN_ID 0x03 // CAN ID packet data
#define ACK_CAN_ID 0x05 // CAN ID acknowledge
#define MAX_FW_SIZE 0x3FFF // Max size firmware = 256 kB
#define PARAM_COUNT 5 // count data in flash
#define SECTOR_6 0x08040000 // 128KB
#define SECTOR_6_END (SECTOR_6 + 128 * 1024) // sector 6 end
// Flash keys for unlocking flash memory
#define BYTE32 0
#define BYTE8 1
//FLASH SET ONE PROGRAMM WORD
#define FLASH_8BYTE FLASH->CR &= ~FLASH_CR_PSIZE & ~FLASH_CR_PSIZE_1
#define FLASH_32BYTE \
FLASH->CR = (FLASH->CR & ~FLASH_CR_PSIZE) | (0x2 << FLASH_CR_PSIZE_Pos)
// Flash command bits
#define FLASH_LOCK FLASH->CR |= FLASH_CR_LOCK
#define FLASH_UNLOCK FLASH->KEYR = FLASH_KEY1; FLASH->KEYR = FLASH_KEY2
// Flash status flags
#define FLASH_BUSY (FLASH->SR & FLASH_SR_BSY)
#define FLASH_ERROR (FLASH->SR & (FLASH_SR_WRPERR | FLASH_SR_PGAERR | FLASH_SR_PGPERR | FLASH_SR_PGSERR))
//for bootloader
typedef void(*pFunction)(void);
/* for start addr in FLASH */
static uint32_t write_ptr = SECTOR_6;
static uint32_t ptr_fl = APP_ADDRESS;
// Function prototypes
void flash_unlock(void);
void flash_lock(void);
void erase_sector(uint8_t sector);
void flash_program_word(uint32_t address, uint32_t data,uint32_t byte_len);
uint8_t flash_read_word(uint32_t address);
FLASH_RECORD* load_params();
void compact_page();
void flash_read(uint32_t addr,FLASH_RECORD* ptr);
uint16_t validate_crc16(uint8_t *data,uint32_t length);
void flash_write(uint32_t addr, FLASH_RECORD* record);
void write_flash_page(const uint8_t* data, uint16_t len);
void erase_flash_pages();
void write_param(uint8_t param_id,uint32_t val);
uint16_t calc_crc_struct(FLASH_RECORD* res);
#endif /* FLASH_H_ */

View file

@ -0,0 +1,38 @@
#pragma once
#pragma region "Motor and sensor setup"
#define LED1 PC10
#define LED2 PC11
#define HARDWARE_SERIAL_RX_PIN PB7
#define HARDWARE_SERIAL_TX_PIN PB6
#define AS5045_CS PB15
#define AS5045_MISO PB14
#define AS5045_MOSI PC1
#define AS5045_SCLK PB10
#define CURRENT_SENSOR_1 PB1
#define CURRENT_SENSOR_2 PB0
#define CURRENT_SENSOR_3 PC5
#define TIM1_CH1 PA8
#define TIM1_CH2 PA9
#define TIM1_CH3 PA10
#define EN_W_GATE_DRIVER PC6
#define EN_U_GATE_DRIVER PA11
#define EN_V_GATE_DRIVER PA12
#define SLEEP_DRIVER PC9
#define RESET_DRIVER PC8
#define FAULT_DRIVER PC7
#define POLE_PAIRS 14
#define CAN2_TX PB13
#define CAN2_RX PB12
#define CAN1_TX PB9
#define CAN1_RX PB8
#define GM6208_RESISTANCE 31
#define OWN_RESISTANCE 26
#pragma endregion
#if !defined(HAL_CAN_MODULE_ENABLED)
#define HAL_CAN_MODULE_ENABLED
#endif
#include "stm32f4xx_hal.h"
#include "stm32f4xx_hal_can.h"
#include <STM32_CAN.h>

View file

@ -0,0 +1,38 @@
#ifndef REG_CAH_H_
#define REG_CAH_H_
#define APP_ADDR 0x0800400 // 16KB - Application
#define ADDR_VAR 0x8040000
#define REG_READ 0x07
#define REG_WRITE 0x08
/* Startup ID device */
#define START_ID 0x00
/* CAN REGISTER ID */
#define REG_ID 0x01
#define REG_BAUDRATE 0x02
#define REG_MOTOR_POSPID_Kp 0x30
#define REG_MOTOR_POSPID_Ki 0x31
#define REG_MOTOR_POSPID_Kd 0x32
#define REG_MOTOR_VELPID_Kp 0x40
#define REG_MOTOR_VELPID_Ki 0x41
#define REG_MOTOR_VELPID_Kd 0x42
#define REG_MOTOR_IMPPID_Kp 0x50
#define REG_MOTOR_IMPPID_Kd 0x51
#define REG_RESET 0x88
#define REG_LED_BLINK 0x8B
#define FOC_STATE 0x60
#define MOTOR_VELOCITY 0x70
#define MOTOR_ENABLED 0x71
#define MOTOR_ANGLE 0x72
#endif // REG_CAH_H_

View file

@ -16,6 +16,16 @@ board = genericSTM32F446RE
framework = arduino
upload_protocol = stlink
debug_tool = stlink
monitor_speed = 115200
monitor_speed = 19200
monitor_parity = N
lib_deps = askuric/Simple FOC@^2.3.2
build_flags =
-DSTM32F446xx
-D HAL_CAN_MODULE_ENABLED
-D SIMPLEFOC_PWM_LOWSIDE_ACTIVE_HIGH
lib_deps =
askuric/Simple FOC@^2.3.4
pazi88/STM32_CAN@^1.1.2
extra_scripts =
pre:gen_compile_commands.py
post:hex_compile.py

View file

@ -0,0 +1,272 @@
#include "flash.h"
#include <stdbool.h>
#include "hal_conf_extra.h"
void flash_unlock(){
// Check if flash is locked
if(!(FLASH->CR & FLASH_CR_LOCK)) {
return; // Already unlocked
}
// Write flash key sequence to unlock
FLASH->KEYR = 0x45670123; // First key
FLASH->KEYR = 0xCDEF89AB; // Second key
}
void flash_lock() {
if(FLASH->CR & FLASH_CR_LOCK) {
return; // Already locked
}
FLASH->CR |= FLASH_CR_LOCK; // Lock flash memory
}
void erase_sector(uint8_t sector){
// Wait if flash is busy
while(FLASH_BUSY);
// Check if flash is locked and unlock if needed
if(FLASH->CR & FLASH_CR_LOCK) {
flash_unlock();
}
// Set sector erase bit and sector number
FLASH->CR |= FLASH_CR_SER;
FLASH->CR &= ~FLASH_CR_SNB;
FLASH->CR |= (sector << FLASH_CR_SNB_Pos) & FLASH_CR_SNB_Msk;
// Start erase
FLASH->CR |= FLASH_CR_STRT;
// Wait for erase to complete
while(FLASH_BUSY);
// Clear sector erase bit
FLASH->CR &= ~FLASH_CR_SER;
}
void flash_program_word(uint32_t address,uint32_t data,uint32_t byte_len){
// Wait if flash is busy
while(FLASH_BUSY);
// Check if flash is locked and unlock if needed
if(FLASH->CR & FLASH_CR_LOCK) {
flash_unlock();
}
// Set program bit 32bit programm size and Write data to address
if(byte_len == 1) {
FLASH_8BYTE;
FLASH->CR |= FLASH_CR_PG;
*(volatile uint8_t*)address = (uint8_t)data;
} else {
FLASH_32BYTE;
FLASH->CR |= FLASH_CR_PG;
*(volatile uint32_t*)address = data;
}
// Wait for programming to complete
while(FLASH_BUSY);
// Clear program bit
FLASH->CR &= ~FLASH_CR_PG;
}
void flash_write(uint32_t addr, FLASH_RECORD* record){
uint32_t* data = (uint32_t*)record;
uint32_t size = FLASH_RECORD_SIZE / 4; //count words in struct
// Wait if flash is busy
while(FLASH_BUSY);
// Check if flash is locked and unlock if needed
if(FLASH->CR & FLASH_CR_LOCK) {
flash_unlock();
}
// Set program bit and write data to flash
FLASH_32BYTE;
FLASH->CR |= FLASH_CR_PG;
for(int i = 0;i < size;i++){
*(volatile uint32_t*)(addr + (i * 4)) = data[i];
}
// Clear program bit
FLASH->CR &= ~FLASH_CR_PG;
write_ptr = addr + (size * 4); //increase variable storing addr
flash_lock();
}
uint8_t flash_read_word(uint32_t address){
// Check if address is valid
if(address < FLASH_BASE || address > FLASH_END) {
return 0;
}
// Read byte from flash memory
return *((volatile uint8_t*)address);
}
// Wait if flash
// bool validata_crc(FLASH_RECORD* crc){
// return crc->crc == 0x6933? true : false;
// }
uint16_t validate_crc16(uint8_t *data, uint32_t length) {
uint16_t crc = 0xFFFF; // start value for CRC MODBUS
while (length--) {
crc ^= *data++; // XOR
for (uint8_t i = 0; i < 8; i++) {
if (crc & 0x0001) {
crc = (crc >> 1) ^ 0xA001; // polynome 0x8005 (reverse)
} else {
crc >>= 1;
}
}
}
return crc;
}
uint16_t calc_crc_struct(FLASH_RECORD* res){
uint8_t arr_res[FLASH_RECORD_SIZE - 2];
uint16_t crc_res;
/* sorting data without CRC */
arr_res[0] = res->data_id;
arr_res[1] = res->data_type;
/* from 32 to 8 bit */
for(int i = 0;i < 4;i++)
arr_res[i + 2] = (uint8_t)(res->value >> i * 8);
crc_res = validate_crc16(arr_res,FLASH_RECORD_SIZE - 2);
return crc_res;
}
/* read struct from FLASH */
void flash_read(uint32_t addr,FLASH_RECORD* ptr){
uint8_t* flash_ptr = (uint8_t*)addr;
uint8_t* dest = (uint8_t*)ptr;
for(int i = 0;i < FLASH_RECORD_SIZE;i++)
dest[i] = flash_ptr[i];
}
void compact_page(){
FLASH_RECORD latest[PARAM_COUNT] = {0};
for(int i = (uint32_t)SECTOR_6;i < (uint32_t)SECTOR_6_END;i += FLASH_RECORD_SIZE) {
FLASH_RECORD rec;
flash_read(i,&rec);
uint16_t calculated_crc = calc_crc_struct(&rec);
if (calculated_crc == rec.crc && rec.data_id < PARAM_COUNT) {
// if the crc does not match, we check further
latest[rec.data_id] = rec;
}
else
// if
continue;
}
erase_sector(6);
write_ptr = SECTOR_6; // Сброс на начало
for (int i = 0; i < PARAM_COUNT; i++) {
if (latest[i].data_id != 0xFF) {
// alignment
if (write_ptr % 4 != 0) {
write_ptr += (4 - (write_ptr % 4));
}
flash_write(write_ptr, &latest[i]);
}
}
}
void write_param(uint8_t param_id, uint32_t val) {
FLASH_RECORD param_flash;
// __disable_irq(); // Interrupt off
param_flash.data_id = param_id;
param_flash.value = val;
param_flash.data_type = sizeof(uint8_t);
param_flash.crc = calc_crc_struct(&param_flash);
// check alignment
if (write_ptr % 8 != 0) {
write_ptr += (8 - (write_ptr % 8));
}
// check buffer overflow
if (write_ptr + FLASH_RECORD_SIZE >= SECTOR_6_END) {
compact_page(); // after compact_page update
// alignment
if (write_ptr % 8 != 0) {
write_ptr += (8 - (write_ptr % 8));
}
}
flash_write(write_ptr, &param_flash); //inside the function, the write_ptr pointer is automatically incremented by the size of the structure
// __enable_irq(); // Interrupt on
}
void write_flash_page(const uint8_t* data, uint16_t len) { // Добавлен const
flash_unlock();
uint32_t word = 0;
for (uint16_t i = 0; i < len; i += 4) {
memcpy(&word, &data[i], 4); // Безопасное копирование
HAL_FLASH_Program(FLASH_TYPEPROGRAM_WORD, ptr_fl + i, word);
}
ptr_fl += len;
flash_lock();
}
void erase_flash_pages() {
FLASH_EraseInitTypeDef erase;
erase.TypeErase = FLASH_TYPEERASE_SECTORS;
erase.Sector = FLASH_SECTOR_2;
erase.NbSectors = 4;
erase.VoltageRange = FLASH_VOLTAGE_RANGE_3;
uint32_t error;
flash_unlock();
HAL_FLASHEx_Erase(&erase, &error);
flash_lock();
}
FLASH_RECORD* load_params(){
__disable_irq();
static FLASH_RECORD latest[PARAM_COUNT] = {0};
FLASH_RECORD res;
for(uint32_t addr = SECTOR_6;addr < SECTOR_6_END;addr +=FLASH_RECORD_SIZE) {
flash_read(addr,&res);
uint16_t calculated_crc = calc_crc_struct(&res);
if (calculated_crc != res.crc || res.data_id >= PARAM_COUNT) continue;
else{
latest[res.data_id] = res;
write_ptr = addr + FLASH_RECORD_SIZE;
}
}
__enable_irq();
return latest;
}

View file

@ -0,0 +1,171 @@
#include "Arduino.h"
#include <STM32_CAN.h>
#include "flash.h"
STM32_CAN Can(CAN2, DEF);
volatile bool fw_update = false;
volatile bool app_valid = false;
volatile uint32_t fw_size = 0;
volatile uint16_t fw_crc = 0;
volatile uint32_t jump;
static FLASH_RECORD *flash_record = {0};
static uint32_t ptr_flash;
volatile uint32_t msg_id;
volatile uint16_t id_x;
volatile uint8_t msg_ch;
// Прототипы функций
void jump_to_app();
void process_can_message(const CAN_message_t &msg);
void erase_flash_pages();
bool verify_firmware();
void send_ack(uint8_t status);
bool is_app_valid();
void setup() {
Serial.setRx(HARDWARE_SERIAL_RX_PIN);
Serial.setTx(HARDWARE_SERIAL_TX_PIN);
Serial.begin(115200);
Can.begin();
Can.setBaudRate(1000000);
TIM_TypeDef *Instance = TIM2;
HardwareTimer *SendTimer = new HardwareTimer(Instance);
SendTimer->setOverflow(100, HERTZ_FORMAT); // 50 Hz
SendTimer->resume();
Can.setFilter(0, 0, STD);
// Настройка GPIO
RCC->AHB1ENR |= RCC_AHB1ENR_GPIOCEN;
GPIOC->MODER |= GPIO_MODER_MODE10_0 | GPIO_MODER_MODE11_0;
GPIOC->ODR &= ~GPIO_ODR_OD11;
GPIOC->ODR |= GPIO_ODR_OD10;
flash_record = load_params();
if(flash_record[firmw].value == UPDATE_FLAG) {
fw_update = true;
for(int i = 0; i < 5;i++){
GPIOC->ODR ^= GPIO_ODR_OD10; // Indecate message
delay(100);
}
// write_param(firmw,0); //reset flasg
erase_flash_pages();
}
else{
// for st-link update, because he doesnt reset flag_update
if(is_app_valid()) jump_to_app(); //firmware exist
else fw_update = true; //firmware doesnt exist, but we in bootloader
}
GPIOC->ODR |= GPIO_ODR_OD10;
}
void process_can_message(const CAN_message_t &msg) {
msg_id = msg.id;
/* 0x697
69 - slave addr
7 || 8 - REG_READ or REG_WRITE */
id_x = (msg_id >> 4) & 0xFFFF; // saved address
msg_ch = msg_id & 0xF; // saved id
if(id_x == flash_record[addr_id].value){
switch(msg_ch) {
case BOOT_CAN_ID:
if(msg.buf[0] == 0x01) { // start transfer
fw_size = *(uint32_t*)&msg.buf[1]; //size of firmware
fw_crc = *(uint16_t*)&msg.buf[5]; //crc
ptr_flash = APP_ADDRESS;
send_ack(0x01);
}
break;
case DATA_CAN_ID: // Data packet
if(ptr_flash < (APP_ADDRESS + fw_size)) {
write_flash_page((const uint8_t*)msg.buf, msg.len);
ptr_flash += msg.len;
send_ack(0x02);
}
break;
case BOOT_CAN_END: // End of transfer
if(verify_firmware()) {
send_ack(0xAA);
write_param(firmw,0); //reset flag set 0
fw_update = false; //reset flag
// erase_sector(7);
delay(500);
NVIC_SystemReset();
} else {
send_ack(0x55);
erase_flash_pages(); //if error
}
break;
}
}
}
void jump_to_app() {
__disable_irq();
jump = *(volatile uint32_t*)(APP_ADDRESS + 4);
void (*app_entry)(void);
app_entry = (void (*)(void))jump;
for (uint32_t i = 0; i < 8; i++) {
NVIC->ICPR[i] = 0xFFFFFFFF;
}
__set_MSP(*(volatile uint32_t*)APP_ADDRESS);
// SCB->VTOR = (uint32_t)0x08008004;
app_entry();
}
bool verify_firmware() {
uint16_t calculated_crc = 0;
calculated_crc = validate_crc16((uint8_t*)APP_ADDRESS,fw_size);
return (calculated_crc == fw_crc);
}
void send_ack(uint8_t status) {
CAN_message_t ack;
ack.id = ACK_CAN_ID;
ack.len = 1;
ack.buf[0] = status;
Can.write(ack);
}
bool is_app_valid() {
volatile uint32_t* app_vector = (volatile uint32_t*)APP_ADDRESS;
// Check stack pointer
bool sp_valid = (app_vector[0] >= 0x20000000) &&
(app_vector[0] <= (0x20000000 + 128*1024)); // Для STM32 с 128K RAM
// check reset_handler
bool pc_valid = (app_vector[1] >= 0x08000000) &&
(app_vector[1] <= (0x08000000 + 1024*1024)); // Для 1MB Flash
// check two words on reset value
bool not_erased = (app_vector[0] != 0xFFFFFFFF) &&
(app_vector[1] != 0xFFFFFFFF);
return sp_valid && pc_valid && not_erased;
}
void loop() {
if(fw_update) {
CAN_message_t msg;
while(Can.read(msg))
process_can_message(msg);
}
}

View file

@ -0,0 +1,141 @@
import can
import sys
import time
from intelhex import IntelHex
# Конфигурация
CAN_CHANNEL = 'socketcan'
CAN_INTERFACE = 'can0'
CAN_BITRATE = 1000000
#ch =int(input("Введите id устройства:"))
ch = int(sys.argv[2])
BOOT_CAN_ID = (ch * 16) + 1
DATA_CAN_ID = (ch * 16) + 3
BOOT_CAN_END = (ch * 16) + 2
ACK_CAN_ID = 0x05
#конфиг для crc16 ibm
def debug_print(msg):
print(f"[DEBUG] {msg}")
def calculate_crc16(data: bytes) -> int:
crc = 0xFFFF
for byte in data:
crc ^= byte
for _ in range(8):
if crc & 0x0001:
crc = (crc >> 1) ^ 0xA001
else:
crc >>= 1
return crc
def send_firmware(hex_file):
try:
debug_print("Инициализация CAN...")
bus = can.interface.Bus(
channel=CAN_INTERFACE,
bustype=CAN_CHANNEL,
bitrate=CAN_BITRATE
)
debug_print("Чтение HEX-файла...")
ih = IntelHex(hex_file)
binary_data = ih.tobinstr() # Исправлено на tobinstr()
fw_size = len(binary_data)
debug_print(f"Размер прошивки: {fw_size} байт")
# Расчет CRC
debug_print("Расчёт CRC...")
# calculator = Calculator(Crc16.IBM)
fw_crc = calculate_crc16(binary_data)
debug_print(f"CRC: 0x{fw_crc:04X}")
# Отправка START
start_data = bytearray([0x01])
start_data += fw_size.to_bytes(4, 'little')
start_data += fw_crc.to_bytes(2, 'little')
debug_print(f"START: {list(start_data)}")
start_msg = can.Message(
arbitration_id=BOOT_CAN_ID,
data=bytes(start_data),
is_extended_id=False
)
try:
bus.send(start_msg)
except can.CanError as e:
debug_print(f"Ошибка отправки START: {str(e)}")
return
# Ожидание ACK
debug_print("Ожидание ACK...")
ack = wait_for_ack(bus)
if not ack:
debug_print("Таймаут ACK START")
return
debug_print(f"Получен ACK: {list(ack.data)}")
# Отправка данных
packet_size = 8
for i in range(0, len(binary_data), packet_size):
chunk = binary_data[i:i+packet_size]
# Дополнение до 8 байт
if len(chunk) < 8:
chunk += b'\xFF' * (8 - len(chunk))
debug_print(f"Пакет {i//8}: {list(chunk)}")
data_msg = can.Message(
arbitration_id=DATA_CAN_ID,
data=chunk,
is_extended_id=False
)
try:
bus.send(data_msg)
except can.CanError as e:
debug_print(f"Ошибка отправки данных: {str(e)}")
return
ack = wait_for_ack(bus)
if not ack:
debug_print("Таймаут ACK DATA")
return
# Финал
debug_print("Отправка FINISH...")
finish_msg = can.Message(
arbitration_id=BOOT_CAN_END,
data=bytes([0xAA]),
is_extended_id=False
)
bus.send(finish_msg)
ack = wait_for_ack(bus, timeout=1.0)
if ack and ack.data[0] == 0xAA:
debug_print("Прошивка подтверждена!")
else:
debug_print("Ошибка верификации!")
except Exception as e:
debug_print(f"Критическая ошибка: {str(e)}")
finally:
bus.shutdown()
def wait_for_ack(bus, timeout=1.0):
start_time = time.time()
while time.time() - start_time < timeout:
msg = bus.recv(timeout=0.1) # Неблокирующий режим
if msg and msg.arbitration_id == ACK_CAN_ID:
return msg
return None
if __name__ == "__main__":
import sys
if len(sys.argv) != 3:
print("Использование: sudo python3 can_flasher.py firmware.hex")
sys.exit(1)
send_firmware(sys.argv[1])

View file

@ -0,0 +1,70 @@
import can
import time
import sys
# Конфигурация
CAN_INTERFACE = 'can0'
OLD_DEVICE_ID = int(sys.argv[1]) # Текущий ID устройства (по умолчанию)
REG_WRITE = 0x8 # Код команды чтения
REG_ID = 0x55 # Адрес регистра с Firmware Update
def send_can_message(bus, can_id, data):
"""Отправка CAN-сообщения"""
try:
msg = can.Message(
arbitration_id=can_id,
data=data,
is_extended_id=False
)
bus.send(msg)
print(f"[Отправка] CAN ID: 0x{can_id:03X}, Данные: {list(data)}")
return True
except can.CanError as e:
print(f"Ошибка CAN: {e}")
return False
def validate_crc16(data):
"""Расчет CRC16 (MODBUS) для проверки целостности данных"""
crc = 0xFFFF
for byte in data:
crc ^= byte
for _ in range(8):
if crc & 0x0001:
crc = (crc >> 1) ^ 0xA001
else:
crc >>= 1
return crc
# Инициализация CAN-интерфейса
bus = can.interface.Bus(channel=CAN_INTERFACE, bustype='socketcan')
# ======= 1. Запрос текущего ID устройства =======
# Формируем CAN ID для чтения: (OLD_DEVICE_ID << 4) | REG_READ
can_id_read = (OLD_DEVICE_ID << 4) | REG_WRITE
# Данные для запроса: [регистр, резервный байт]
data_read = [REG_ID, 0x00]
# Формируем полные данные для расчета CRC:
# - CAN ID разбивается на 2 байта (little-endian)
# - Добавляем данные запроса
full_data_for_crc = list(can_id_read.to_bytes(2, 'little')) + data_read
# Рассчитываем CRC и разбиваем на байты (little-endian)
crc = validate_crc16(full_data_for_crc)
crc_bytes = list(crc.to_bytes(2, 'little'))
# Собираем итоговый пакет: данные + CRC
packet_read = data_read + crc_bytes
print("Переход в boot режим", packet_read)
send_can_message(bus, can_id_read, packet_read)
bus.shutdown()
if __name__ == "__main__":
import sys
if len(sys.argv) != 2:
print("Использование: python3 firmware_test.py address")
sys.exit(1)

View file

@ -0,0 +1,78 @@
import subprocess
import os
import sys
def flash_hex_with_stlink(hex_file_path):
if not os.path.isfile(hex_file_path):
print(f"❌ Файл не найден: {hex_file_path}")
return False
command = [
"st-flash",
"--format", "ihex",
"write",
hex_file_path
]
try:
print(f"⚡️ Прошиваем {hex_file_path} через ST-Link...")
result = subprocess.run(
command,
stdout=subprocess.PIPE,
stderr=subprocess.PIPE,
universal_newlines=True,
timeout=30
)
print("▬▬▬ STDOUT ▬▬▬")
print(result.stdout)
print("▬▬▬ STDERR ▬▬▬")
print(result.stderr)
if result.returncode == 0:
print("✅ Прошивка успешно завершена!")
# Добавленный блок сброса
try:
print("🔄 Выполняем сброс устройства...")
reset_result = subprocess.run(
["st-info", "--reset"],
stdout=subprocess.PIPE,
stderr=subprocess.PIPE,
universal_newlines=True,
timeout=10
)
if reset_result.returncode == 0:
print("♻️ Устройство успешно сброшено!")
else:
print(f"⚠️ Ошибка (код: {reset_result.returncode})")
print("▬▬▬ STDERR сброса ▬▬▬")
print(reset_result.stderr)
except Exception as e:
print(f"⚠️ Ошибка при сбросе: {str(e)}")
return True
else:
print(f"❌ Ошибка прошивки (код: {result.returncode})")
return False
except FileNotFoundError:
print("❌ st-flash не найден! Установите stlink-tools.")
return False
except subprocess.TimeoutExpired:
print("❌ Таймаут операции! Проверьте подключение ST-Link.")
return False
except Exception as e:
print(f"❌ Неизвестная ошибка: {str(e)}")
return False
if __name__ == "__main__":
if len(sys.argv) != 2:
print("Использование: python stlink_flash.py <firmware.hex>")
sys.exit(1)
if flash_hex_with_stlink(sys.argv[1]):
sys.exit(0)
else:
sys.exit(1)

View file

@ -0,0 +1,100 @@
import subprocess
import os
import sys
import time
def flash_hex_with_stlink(hex_file_path, component_name):
if not os.path.isfile(hex_file_path):
print(f"❌ Файл {component_name} не найден: {hex_file_path}")
return False
command = [
"st-flash",
"--format", "ihex",
"write",
hex_file_path
]
try:
print(f"⚡️ Прошиваем {component_name} ({hex_file_path}) через ST-Link...")
result = subprocess.run(
command,
stdout=subprocess.PIPE,
stderr=subprocess.PIPE,
universal_newlines=True,
timeout=30
)
print("▬▬▬ STDOUT ▬▬▬")
print(result.stdout)
print("▬▬▬ STDERR ▬▬▬")
print(result.stderr)
if result.returncode == 0:
print(f"{component_name} успешно прошит!")
return True
else:
print(f"❌ Ошибка прошивки {component_name} (код: {result.returncode})")
return False
except FileNotFoundError:
print("❌ st-flash не найден! Установите stlink-tools.")
return False
except subprocess.TimeoutExpired:
print(f"❌ Таймаут операции при прошивке {component_name}! Проверьте подключение ST-Link.")
return False
except Exception as e:
print(f"❌ Неизвестная ошибка при прошивке {component_name}: {str(e)}")
return False
def reset_device():
try:
print("🔄 Выполняем сброс(перезагрузку) устройства...")
reset_result = subprocess.run(
["st-info", "--reset"],
stdout=subprocess.PIPE,
stderr=subprocess.PIPE,
universal_newlines=True,
timeout=10
)
if reset_result.returncode == 0:
print("♻️ Устройство успешно сброшено!")
return True
else:
print(f"⚠️ Ошибка при сбросе (код: {reset_result.returncode})")
print("▬▬▬ STDERR сброса ▬▬▬")
print(reset_result.stderr)
return False
except Exception as e:
print(f"⚠️ Ошибка при сбросе: {str(e)}")
return False
if __name__ == "__main__":
if len(sys.argv) != 3:
print("Использование: python stlink_flash.py <bootloader.hex> <application.hex>")
print("Пример: python stlink_flash.py bootloader.hex firmware.hex")
sys.exit(1)
bootloader_path = sys.argv[1]
app_path = sys.argv[2]
# Прошиваем сначала бутлоадер
if not flash_hex_with_stlink(bootloader_path, "Bootloader"):
print("\n💥 Ошибка прошивки бутлоадера!")
sys.exit(1)
# Сбрасываем устройство после прошивки бутлоадера
reset_device()
time.sleep(1) # Короткая пауза
# Прошиваем основное приложение
if not flash_hex_with_stlink(app_path, "Application"):
print("\n💥 Ошибка прошивки основного приложения!")
sys.exit(1)
# Финальный сброс устройства
reset_device()
print("\n🎉 Все компоненты успешно прошиты!")
sys.exit(0)

View file

@ -0,0 +1 @@
Checks: '-*, -misc-definitions-in-headers'

View file

@ -0,0 +1,18 @@
CompileFlags:
Add:
[
# -mlong-calls,
-DSSIZE_MAX,
-DLWIP_NO_UNISTD_H=1,
-Dssize_t=long,
-D_SSIZE_T_DECLARED,
]
Remove:
[
-fno-tree-switch-conversion,
-mtext-section-literals,
-mlongcalls,
-fstrict-volatile-bitfields,
-free,
-fipa-pta,
]

10
controller/fw/embed/.gitignore vendored Normal file
View file

@ -0,0 +1,10 @@
.pio
.vscode/.browse.c_cpp.db*
.vscode/c_cpp_properties.json
.vscode/launch.json
.vscode/ipch
.cache/
.metadata/
cubemx_config/
compile_commands.json
../embed.rar

View file

@ -0,0 +1,19 @@
Import("env")
# Получаем путь к компилятору из окружения PlatformIO
gcc_path = env.subst("$CC")
# Выполняем команду для получения версии компилятора
import subprocess
try:
result = subprocess.run([gcc_path, "--version"], stdout=subprocess.PIPE, stderr=subprocess.PIPE, text=True)
if result.returncode == 0:
print(f"GCC version: {result.stdout}")
else:
print(f"Failed to get GCC version: {result.stderr}")
except Exception as e:
print(f"Error while getting GCC version: {e}")
# Дополнительно проверяем путь к компилятору
print(f"Compiler path: {gcc_path}")

View file

@ -0,0 +1,299 @@
#MicroXplorer Configuration settings - do not modify
ADC2.Channel-1\#ChannelRegularConversion=ADC_CHANNEL_15
ADC2.Channel-5\#ChannelRegularConversion=ADC_CHANNEL_8
ADC2.Channel-6\#ChannelRegularConversion=ADC_CHANNEL_9
ADC2.EOCSelection=ADC_EOC_SEQ_CONV
ADC2.IPParameters=Rank-1\#ChannelRegularConversion,Channel-1\#ChannelRegularConversion,SamplingTime-1\#ChannelRegularConversion,NbrOfConversionFlag,InjNumberOfConversion,NbrOfConversion,Rank-5\#ChannelRegularConversion,Channel-5\#ChannelRegularConversion,SamplingTime-5\#ChannelRegularConversion,Rank-6\#ChannelRegularConversion,Channel-6\#ChannelRegularConversion,SamplingTime-6\#ChannelRegularConversion,EOCSelection
ADC2.InjNumberOfConversion=0
ADC2.NbrOfConversion=3
ADC2.NbrOfConversionFlag=1
ADC2.Rank-1\#ChannelRegularConversion=1
ADC2.Rank-5\#ChannelRegularConversion=2
ADC2.Rank-6\#ChannelRegularConversion=3
ADC2.SamplingTime-1\#ChannelRegularConversion=ADC_SAMPLETIME_3CYCLES
ADC2.SamplingTime-5\#ChannelRegularConversion=ADC_SAMPLETIME_3CYCLES
ADC2.SamplingTime-6\#ChannelRegularConversion=ADC_SAMPLETIME_3CYCLES
FREERTOS.IPParameters=Tasks01,configENABLE_FPU,configTIMER_TASK_PRIORITY
FREERTOS.Tasks01=defaultTask,24,128,StartDefaultTask,Default,NULL,Dynamic,NULL,NULL
FREERTOS.configENABLE_FPU=1
FREERTOS.configTIMER_TASK_PRIORITY=1
File.Version=6
GPIO.groupedBy=Group By Peripherals
KeepUserPlacement=false
Mcu.CPN=STM32F446RET6
Mcu.Family=STM32F4
Mcu.IP0=ADC2
Mcu.IP1=FREERTOS
Mcu.IP2=NVIC
Mcu.IP3=RCC
Mcu.IP4=SPI2
Mcu.IP5=SYS
Mcu.IP6=TIM1
Mcu.IP7=TIM3
Mcu.IP8=TIM5
Mcu.IP9=USART1
Mcu.IPNb=10
Mcu.Name=STM32F446R(C-E)Tx
Mcu.Package=LQFP64
Mcu.Pin0=PC1
Mcu.Pin1=PC5
Mcu.Pin10=PC9
Mcu.Pin11=PA8
Mcu.Pin12=PA9
Mcu.Pin13=PA10
Mcu.Pin14=PA11
Mcu.Pin15=PA12
Mcu.Pin16=PA13
Mcu.Pin17=PA14
Mcu.Pin18=PC10
Mcu.Pin19=PC11
Mcu.Pin2=PB0
Mcu.Pin20=PC12
Mcu.Pin21=PD2
Mcu.Pin22=PB6
Mcu.Pin23=PB7
Mcu.Pin24=VP_FREERTOS_VS_CMSIS_V2
Mcu.Pin25=VP_SYS_VS_tim2
Mcu.Pin26=VP_TIM1_VS_ClockSourceINT
Mcu.Pin27=VP_TIM3_VS_ClockSourceINT
Mcu.Pin28=VP_TIM5_VS_ClockSourceINT
Mcu.Pin3=PB1
Mcu.Pin4=PB10
Mcu.Pin5=PB14
Mcu.Pin6=PB15
Mcu.Pin7=PC6
Mcu.Pin8=PC7
Mcu.Pin9=PC8
Mcu.PinsNb=29
Mcu.ThirdPartyNb=0
Mcu.UserConstants=
Mcu.UserName=STM32F446RETx
MxCube.Version=6.5.0
MxDb.Version=DB.6.0.50
NVIC.ADC_IRQn=true\:5\:0\:true\:true\:true\:1\:true\:true\:true\:true
NVIC.BusFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false\:false
NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false\:false
NVIC.ForceEnableDMAVector=true
NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false\:false
NVIC.MemoryManagement_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false\:false
NVIC.NonMaskableInt_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false\:false
NVIC.PendSV_IRQn=true\:15\:0\:false\:false\:false\:true\:false\:false\:false
NVIC.PriorityGroup=NVIC_PRIORITYGROUP_4
NVIC.SPI2_IRQn=true\:5\:0\:false\:false\:true\:true\:true\:true\:true
NVIC.SVCall_IRQn=true\:0\:0\:false\:false\:false\:false\:false\:false\:false
NVIC.SavedPendsvIrqHandlerGenerated=true
NVIC.SavedSvcallIrqHandlerGenerated=true
NVIC.SavedSystickIrqHandlerGenerated=true
NVIC.SysTick_IRQn=true\:15\:0\:false\:false\:false\:true\:false\:true\:false
NVIC.TIM2_IRQn=true\:15\:0\:true\:false\:true\:false\:false\:true\:true
NVIC.TIM3_IRQn=true\:5\:0\:false\:false\:true\:true\:true\:true\:true
NVIC.TimeBase=TIM2_IRQn
NVIC.TimeBaseIP=TIM2
NVIC.UsageFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false\:false
PA10.Signal=S_TIM1_CH3
PA11.GPIOParameters=GPIO_Speed,GPIO_PuPd,GPIO_Label
PA11.GPIO_Label=EN_U
PA11.GPIO_PuPd=GPIO_PULLDOWN
PA11.GPIO_Speed=GPIO_SPEED_FREQ_HIGH
PA11.Locked=true
PA11.Signal=GPIO_Output
PA12.GPIOParameters=GPIO_Speed,GPIO_PuPd,GPIO_Label
PA12.GPIO_Label=EN_V
PA12.GPIO_PuPd=GPIO_PULLDOWN
PA12.GPIO_Speed=GPIO_SPEED_FREQ_HIGH
PA12.Locked=true
PA12.Signal=GPIO_Output
PA13.Mode=Serial_Wire
PA13.Signal=SYS_JTMS-SWDIO
PA14.Mode=Serial_Wire
PA14.Signal=SYS_JTCK-SWCLK
PA8.Signal=S_TIM1_CH1
PA9.Signal=S_TIM1_CH2
PB0.GPIOParameters=GPIO_Label
PB0.GPIO_Label=SENSE2
PB0.Locked=true
PB0.Signal=ADCx_IN8
PB1.GPIOParameters=GPIO_Label
PB1.GPIO_Label=SENSE1
PB1.Locked=true
PB1.Signal=ADCx_IN9
PB10.Locked=true
PB10.Mode=Full_Duplex_Master
PB10.Signal=SPI2_SCK
PB14.Locked=true
PB14.Mode=Full_Duplex_Master
PB14.Signal=SPI2_MISO
PB15.GPIOParameters=GPIO_Speed,PinState,GPIO_PuPd,GPIO_Label
PB15.GPIO_Label=AS5045_CS
PB15.GPIO_PuPd=GPIO_PULLUP
PB15.GPIO_Speed=GPIO_SPEED_FREQ_VERY_HIGH
PB15.Locked=true
PB15.PinState=GPIO_PIN_SET
PB15.Signal=GPIO_Output
PB6.Mode=Asynchronous
PB6.Signal=USART1_TX
PB7.Mode=Asynchronous
PB7.Signal=USART1_RX
PC1.Mode=Full_Duplex_Master
PC1.Signal=SPI2_MOSI
PC10.GPIOParameters=GPIO_Label
PC10.GPIO_Label=LED1
PC10.Locked=true
PC10.Signal=GPIO_Output
PC11.GPIOParameters=GPIO_Label
PC11.GPIO_Label=LED2
PC11.Locked=true
PC11.Signal=GPIO_Output
PC12.GPIOParameters=GPIO_Label
PC12.GPIO_Label=LED3
PC12.Locked=true
PC12.Signal=GPIO_Output
PC5.GPIOParameters=GPIO_Label
PC5.GPIO_Label=SENSE3
PC5.Locked=true
PC5.Signal=ADCx_IN15
PC6.GPIOParameters=GPIO_Speed,GPIO_PuPd,GPIO_Label
PC6.GPIO_Label=EN_W
PC6.GPIO_PuPd=GPIO_PULLDOWN
PC6.GPIO_Speed=GPIO_SPEED_FREQ_HIGH
PC6.Locked=true
PC6.Signal=GPIO_Output
PC7.GPIOParameters=GPIO_Label
PC7.GPIO_Label=DRV_FAULT
PC7.Locked=true
PC7.Signal=GPIO_Input
PC8.GPIOParameters=GPIO_Label
PC8.GPIO_Label=DRV_RESET
PC8.Locked=true
PC8.Signal=GPIO_Output
PC9.GPIOParameters=GPIO_Label
PC9.GPIO_Label=DRV_SLEEP
PC9.Locked=true
PC9.Signal=GPIO_Output
PD2.GPIOParameters=GPIO_Speed,GPIO_PuPd,GPIO_Label
PD2.GPIO_Label=spi1_cs
PD2.GPIO_PuPd=GPIO_PULLDOWN
PD2.GPIO_Speed=GPIO_SPEED_FREQ_VERY_HIGH
PD2.Locked=true
PD2.Signal=GPIO_Output
PinOutPanel.RotationAngle=0
ProjectManager.AskForMigrate=true
ProjectManager.BackupPrevious=false
ProjectManager.CompilerOptimize=6
ProjectManager.ComputerToolchain=false
ProjectManager.CoupleFile=true
ProjectManager.CustomerFirmwarePackage=
ProjectManager.DefaultFWLocation=true
ProjectManager.DeletePrevious=true
ProjectManager.DeviceId=STM32F446RETx
ProjectManager.FirmwarePackage=STM32Cube FW_F4 V1.27.1
ProjectManager.FreePins=false
ProjectManager.HalAssertFull=false
ProjectManager.HeapSize=0x200
ProjectManager.KeepUserCode=true
ProjectManager.LastFirmware=true
ProjectManager.LibraryCopy=1
ProjectManager.MainLocation=Src
ProjectManager.NoMain=false
ProjectManager.PreviousToolchain=STM32CubeIDE
ProjectManager.ProjectBuild=false
ProjectManager.ProjectFileName=cubemx_config.ioc
ProjectManager.ProjectName=cubemx_config
ProjectManager.RegisterCallBack=
ProjectManager.StackSize=0x400
ProjectManager.TargetToolchain=Other Toolchains (GPDSC)
ProjectManager.ToolChainLocation=
ProjectManager.UnderRoot=false
ProjectManager.functionlistsort=1-MX_GPIO_Init-GPIO-false-HAL-true,2-SystemClock_Config-RCC-false-HAL-false,3-MX_TIM1_Init-TIM1-false-HAL-true,4-MX_USART1_UART_Init-USART1-false-HAL-true,5-MX_SPI2_Init-SPI2-false-HAL-true,6-MX_TIM3_Init-TIM3-false-HAL-true,7-MX_ADC2_Init-ADC2-false-HAL-true,8-MX_TIM5_Init-TIM5-false-HAL-true
RCC.AHBFreq_Value=180000000
RCC.APB1CLKDivider=RCC_HCLK_DIV4
RCC.APB1Freq_Value=45000000
RCC.APB1TimFreq_Value=90000000
RCC.APB2CLKDivider=RCC_HCLK_DIV2
RCC.APB2Freq_Value=90000000
RCC.APB2TimFreq_Value=180000000
RCC.CECFreq_Value=32786.88524590164
RCC.CortexFreq_Value=180000000
RCC.FCLKCortexFreq_Value=180000000
RCC.FMPI2C1Freq_Value=45000000
RCC.FamilyName=M
RCC.HCLKFreq_Value=180000000
RCC.HSE_VALUE=8000000
RCC.I2S1Freq_Value=96000000
RCC.I2S2Freq_Value=96000000
RCC.IPParameters=AHBFreq_Value,APB1CLKDivider,APB1Freq_Value,APB1TimFreq_Value,APB2CLKDivider,APB2Freq_Value,APB2TimFreq_Value,CECFreq_Value,CortexFreq_Value,FCLKCortexFreq_Value,FMPI2C1Freq_Value,FamilyName,HCLKFreq_Value,HSE_VALUE,I2S1Freq_Value,I2S2Freq_Value,MCO2PinFreq_Value,PLLCLKFreq_Value,PLLI2SPCLKFreq_Value,PLLI2SQCLKFreq_Value,PLLI2SRCLKFreq_Value,PLLI2SoutputFreq_Value,PLLM,PLLN,PLLQCLKFreq_Value,PLLRCLKFreq_Value,PLLSAIPCLKFreq_Value,PLLSAIQCLKFreq_Value,PLLSAIoutputFreq_Value,PWRFreq_Value,SAIAFreq_Value,SAIBFreq_Value,SDIOFreq_Value,SPDIFRXFreq_Value,SYSCLKFreq_VALUE,SYSCLKSource,USBFreq_Value,VCOI2SInputFreq_Value,VCOI2SOutputFreq_Value,VCOInputFreq_Value,VCOOutputFreq_Value,VCOSAIInputFreq_Value,VCOSAIOutputFreq_Value
RCC.MCO2PinFreq_Value=180000000
RCC.PLLCLKFreq_Value=180000000
RCC.PLLI2SPCLKFreq_Value=96000000
RCC.PLLI2SQCLKFreq_Value=96000000
RCC.PLLI2SRCLKFreq_Value=96000000
RCC.PLLI2SoutputFreq_Value=96000000
RCC.PLLM=8
RCC.PLLN=180
RCC.PLLQCLKFreq_Value=180000000
RCC.PLLRCLKFreq_Value=180000000
RCC.PLLSAIPCLKFreq_Value=96000000
RCC.PLLSAIQCLKFreq_Value=96000000
RCC.PLLSAIoutputFreq_Value=96000000
RCC.PWRFreq_Value=180000000
RCC.SAIAFreq_Value=96000000
RCC.SAIBFreq_Value=96000000
RCC.SDIOFreq_Value=180000000
RCC.SPDIFRXFreq_Value=180000000
RCC.SYSCLKFreq_VALUE=180000000
RCC.SYSCLKSource=RCC_SYSCLKSOURCE_PLLCLK
RCC.USBFreq_Value=180000000
RCC.VCOI2SInputFreq_Value=1000000
RCC.VCOI2SOutputFreq_Value=192000000
RCC.VCOInputFreq_Value=2000000
RCC.VCOOutputFreq_Value=360000000
RCC.VCOSAIInputFreq_Value=1000000
RCC.VCOSAIOutputFreq_Value=192000000
SH.ADCx_IN15.0=ADC2_IN15,IN15
SH.ADCx_IN15.ConfNb=1
SH.ADCx_IN8.0=ADC2_IN8,IN8
SH.ADCx_IN8.ConfNb=1
SH.ADCx_IN9.0=ADC2_IN9,IN9
SH.ADCx_IN9.ConfNb=1
SH.S_TIM1_CH1.0=TIM1_CH1,PWM Generation1 CH1
SH.S_TIM1_CH1.ConfNb=1
SH.S_TIM1_CH2.0=TIM1_CH2,PWM Generation2 CH2
SH.S_TIM1_CH2.ConfNb=1
SH.S_TIM1_CH3.0=TIM1_CH3,PWM Generation3 CH3
SH.S_TIM1_CH3.ConfNb=1
SPI2.BaudRatePrescaler=SPI_BAUDRATEPRESCALER_64
SPI2.CLKPhase=SPI_PHASE_1EDGE
SPI2.CLKPolarity=SPI_POLARITY_LOW
SPI2.CalculateBaudRate=703.125 KBits/s
SPI2.DataSize=SPI_DATASIZE_16BIT
SPI2.Direction=SPI_DIRECTION_2LINES
SPI2.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate,DataSize,CLKPhase,BaudRatePrescaler,CLKPolarity
SPI2.Mode=SPI_MODE_MASTER
SPI2.VirtualType=VM_MASTER
TIM1.AutoReloadPreload=TIM_AUTORELOAD_PRELOAD_ENABLE
TIM1.BreakState=TIM_BREAK_DISABLE
TIM1.Channel-PWM\ Generation1\ CH1=TIM_CHANNEL_1
TIM1.Channel-PWM\ Generation2\ CH2=TIM_CHANNEL_2
TIM1.Channel-PWM\ Generation3\ CH3=TIM_CHANNEL_3
TIM1.CounterMode=TIM_COUNTERMODE_CENTERALIGNED1
TIM1.IPParameters=Channel-PWM Generation1 CH1,Channel-PWM Generation2 CH2,Channel-PWM Generation3 CH3,TIM_MasterOutputTrigger,AutoReloadPreload,BreakState,OffStateRunMode,OffStateIDLEMode,CounterMode,Period
TIM1.OffStateIDLEMode=TIM_OSSI_DISABLE
TIM1.OffStateRunMode=TIM_OSSR_DISABLE
TIM1.Period=2399
TIM1.TIM_MasterOutputTrigger=TIM_TRGO_RESET
TIM3.IPParameters=Period,Prescaler
TIM3.Period=99
TIM3.Prescaler=89
USART1.IPParameters=VirtualMode
USART1.VirtualMode=VM_ASYNC
VP_FREERTOS_VS_CMSIS_V2.Mode=CMSIS_V2
VP_FREERTOS_VS_CMSIS_V2.Signal=FREERTOS_VS_CMSIS_V2
VP_SYS_VS_tim2.Mode=TIM2
VP_SYS_VS_tim2.Signal=SYS_VS_tim2
VP_TIM1_VS_ClockSourceINT.Mode=Internal
VP_TIM1_VS_ClockSourceINT.Signal=TIM1_VS_ClockSourceINT
VP_TIM3_VS_ClockSourceINT.Mode=Internal
VP_TIM3_VS_ClockSourceINT.Signal=TIM3_VS_ClockSourceINT
VP_TIM5_VS_ClockSourceINT.Mode=Internal
VP_TIM5_VS_ClockSourceINT.Signal=TIM5_VS_ClockSourceINT
board=custom

View file

@ -0,0 +1,178 @@
/**
******************************************************************************
* @file LinkerScript.ld
* @author Auto-generated by STM32CubeIDE
* @brief Linker script for STM32F446RCTx Device from STM32F4 series
* 256Kbytes FLASH
* 128Kbytes RAM
*
* Set heap size, stack size and stack location according
* to application requirements.
*
* Set memory bank area and size if external memory is used
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2020 STMicroelectronics.
* All rights reserved.</center></h2>
*
* This software component is licensed by ST under BSD 3-Clause license,
* the "License"; You may not use this file except in compliance with the
* License. You may obtain a copy of the License at:
* opensource.org/licenses/BSD-3-Clause
*
******************************************************************************
*/
/* Entry Point */
ENTRY(Reset_Handler)
/* Highest address of the user mode stack */
_estack = ORIGIN(RAM) + LENGTH(RAM); /* end of "RAM" Ram type memory */
_Min_Heap_Size = 0x200; /* required amount of heap */
_Min_Stack_Size = 0x400; /* required amount of stack */
/* Memories definition */
MEMORY
{
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = LD_MAX_DATA_SIZE
FLASH (rx) : ORIGIN = 0x8000000 + 0x8000, LENGTH = 512K - 0x8000
}
/* Sections */
SECTIONS
{
/* The startup code into "FLASH" Rom type memory */
.isr_vector :
{
. = ALIGN(4);
KEEP(*(.isr_vector)) /* Startup code */
. = ALIGN(4);
} >FLASH
/* The program code and other data into "FLASH" Rom type memory */
.text :
{
. = ALIGN(4);
*(.text) /* .text sections (code) */
*(.text*) /* .text* sections (code) */
*(.glue_7) /* glue arm to thumb code */
*(.glue_7t) /* glue thumb to arm code */
*(.eh_frame)
KEEP (*(.init))
KEEP (*(.fini))
. = ALIGN(4);
_etext = .; /* define a global symbols at end of code */
} >FLASH
/* Constant data into "FLASH" Rom type memory */
.rodata :
{
. = ALIGN(4);
*(.rodata) /* .rodata sections (constants, strings, etc.) */
*(.rodata*) /* .rodata* sections (constants, strings, etc.) */
. = ALIGN(4);
} >FLASH
.ARM.extab (READONLY) : {
. = ALIGN(4);
*(.ARM.extab* .gnu.linkonce.armextab.*)
. = ALIGN(4);
} >FLASH
.ARM (READONLY) : {
. = ALIGN(4);
__exidx_start = .;
*(.ARM.exidx*)
__exidx_end = .;
. = ALIGN(4);
} >FLASH
.preinit_array (READONLY) :
{
. = ALIGN(4);
PROVIDE_HIDDEN (__preinit_array_start = .);
KEEP (*(.preinit_array*))
PROVIDE_HIDDEN (__preinit_array_end = .);
. = ALIGN(4);
} >FLASH
.init_array (READONLY) :
{
. = ALIGN(4);
PROVIDE_HIDDEN (__init_array_start = .);
KEEP (*(SORT(.init_array.*)))
KEEP (*(.init_array*))
PROVIDE_HIDDEN (__init_array_end = .);
. = ALIGN(4);
} >FLASH
.fini_array (READONLY) :
{
. = ALIGN(4);
PROVIDE_HIDDEN (__fini_array_start = .);
KEEP (*(SORT(.fini_array.*)))
KEEP (*(.fini_array*))
PROVIDE_HIDDEN (__fini_array_end = .);
. = ALIGN(4);
} >FLASH
/* Used by the startup to initialize data */
_sidata = LOADADDR(.data);
/* Initialized data sections into "RAM" Ram type memory */
.data :
{
. = ALIGN(4);
_sdata = .; /* create a global symbol at data start */
*(.data) /* .data sections */
*(.data*) /* .data* sections */
*(.RamFunc) /* .RamFunc sections */
*(.RamFunc*) /* .RamFunc* sections */
. = ALIGN(4);
_edata = .; /* define a global symbol at data end */
} >RAM AT> FLASH
/* Uninitialized data section into "RAM" Ram type memory */
. = ALIGN(4);
.bss :
{
/* This is used by the startup in order to initialize the .bss section */
_sbss = .; /* define a global symbol at bss start */
__bss_start__ = _sbss;
*(.bss)
*(.bss*)
*(COMMON)
. = ALIGN(4);
_ebss = .; /* define a global symbol at bss end */
__bss_end__ = _ebss;
} >RAM
/* User_heap_stack section, used to check that there is enough "RAM" Ram type memory left */
._user_heap_stack :
{
. = ALIGN(8);
PROVIDE ( end = . );
PROVIDE ( _end = . );
. = . + _Min_Heap_Size;
. = . + _Min_Stack_Size;
. = ALIGN(8);
} >RAM
/* Remove information from the compiler libraries */
/DISCARD/ :
{
libc.a ( * )
libm.a ( * )
libgcc.a ( * )
}
.ARM.attributes 0 : { *(.ARM.attributes) }
}

View file

@ -0,0 +1,8 @@
import os
Import("env")
# include toolchain paths
env.Replace(COMPILATIONDB_INCLUDE_TOOLCHAIN=True)
# override compilation DB path
env.Replace(COMPILATIONDB_PATH="compile_commands.json")

View file

@ -0,0 +1,10 @@
Import("env")
# Custom HEX from ELF
env.AddPostAction(
"$BUILD_DIR/${PROGNAME}.elf",
env.VerboseAction(" ".join([
"$OBJCOPY", "-O", "ihex", "-R", ".eeprom",
"$BUILD_DIR/${PROGNAME}.elf", "$BUILD_DIR/${PROGNAME}.hex"
]), "Building $BUILD_DIR/${PROGNAME}.hex")
)

View file

@ -0,0 +1,31 @@
#pragma once
#include "Arduino.h"
#include <AS5045.h>
#include <DRV8313.h>
#include <SimpleFOC.h>
#include <STM32_CAN.h>
#include "flash.h"
extern STM32_CAN Can;
extern SPIClass spi;
extern MagneticSensorAS5045 encoder;
extern BLDCMotor motor;
extern DRV8313Driver driver;
extern LowsideCurrentSense current_sense;
extern Commander command;
struct MotorControlInputs {
float target_angle = 0.0;
float target_velocity = 0.0;
bool motor_enabled = false;
bool foc_state = false;
};
extern MotorControlInputs motor_control_inputs;
void doMotor(char *cmd);
void setup_foc(MagneticSensorAS5045 *encoder, BLDCMotor *motor,
DRV8313Driver *driver, LowsideCurrentSense *current_sense,
FLASH_RECORD* pid_data);
void foc_step(BLDCMotor *motor);

View file

@ -0,0 +1,86 @@
#ifndef FLASH_H_
#define FLASH_H_
#include "stm32f446xx.h"
#include <stdio.h>
#include <stdlib.h>
/* for addr in FLASH */
/* no padding for this struct, beacuse storing 8 bytes*/
typedef struct{
uint8_t data_id; // data_id = id register of can
uint8_t data_type;
uint16_t crc;
uint32_t value;
// uint32_t write_ptr_now;
}FLASH_RECORD;
enum {
addr_id = 0,
pid_p = 1,
pid_i,
pid_d,
firmw,
foc_id,
angl,
vel
};
/* for saved in FLASH float data*/
union{
uint32_t i;
float f;
}conv_float_to_int;
#define FLASH_RECORD_SIZE sizeof(FLASH_RECORD) //size flash struct
#define PARAM_COUNT 5 // count data in flash
#define FIRMWARE_FLAG (uint32_t)0xDEADBEEF
// Flash sectors for STM32F407
#define SECTOR_2 0x08008000 // 16KB
#define SECTOR_3 0x0800C000 // 16KB
#define SECTOR_4 0x08010000 // 64KB
#define SECTOR_5 0x08020000 // 128KB
#define SECTOR_6 0x08040000 // 128KB
#define SECTOR_6_END (SECTOR_6 + 128 * 1024) // sector 6 end
#define SECTOR_7 0x08060000 // 128KB
#define FLAG_BOOT (0x08040000 + 4)
// Flash keys for unlocking flash memory
#define BYTE32 0
#define BYTE8 1
#define UPDATE_FLAG 0xDEADBEEF // Unique 32bit value
//FLASH SET ONE PROGRAMM WORD
#define FLASH_8BYTE FLASH->CR &= ~FLASH_CR_PSIZE & ~FLASH_CR_PSIZE_1
#define FLASH_32BYTE \
FLASH->CR = (FLASH->CR & ~FLASH_CR_PSIZE) | (0x2 << FLASH_CR_PSIZE_Pos)
// Flash command bits
#define FLASH_LOCK FLASH->CR |= FLASH_CR_LOCK
#define FLASH_UNLOCK FLASH->KEYR = FLASH_KEY1; FLASH->KEYR = FLASH_KEY2
// Flash status flags
#define FLASH_BUSY (FLASH->SR & FLASH_SR_BSY)
#define FLASH_ERROR (FLASH->SR & (FLASH_SR_WRPERR | FLASH_SR_PGAERR | FLASH_SR_PGPERR | FLASH_SR_PGSERR))
static uint32_t write_ptr = SECTOR_6;
//for bootloader
typedef void(*pFunction)(void);
// Function prototypes
void flash_unlock(void);
void flash_lock(void);
void erase_sector(uint8_t sector);
void flash_program_word(uint32_t address, uint32_t data,uint32_t byte_len);
uint8_t flash_read_word(uint32_t address);
FLASH_RECORD* load_params();
void compact_page();
void flash_read(uint32_t addr,FLASH_RECORD* ptr);
uint16_t validate_crc16(uint8_t *data,uint32_t length);
void flash_write(uint32_t addr, FLASH_RECORD* record);
bool validaate_crc(FLASH_RECORD* crc);
void write_param(uint8_t param_id,uint32_t val);
#endif /* FLASH_H_ */

View file

@ -0,0 +1,38 @@
#pragma once
#pragma region "Motor and sensor setup"
#define LED1 PC10
#define LED2 PC11
#define HARDWARE_SERIAL_RX_PIN PB7
#define HARDWARE_SERIAL_TX_PIN PB6
#define AS5045_CS PB15
#define AS5045_MISO PB14
#define AS5045_MOSI PC1
#define AS5045_SCLK PB10
#define CURRENT_SENSOR_1 PB1
#define CURRENT_SENSOR_2 PB0
#define CURRENT_SENSOR_3 PC5
#define TIM1_CH1 PA8
#define TIM1_CH2 PA9
#define TIM1_CH3 PA10
#define EN_W_GATE_DRIVER PC6
#define EN_U_GATE_DRIVER PA11
#define EN_V_GATE_DRIVER PA12
#define SLEEP_DRIVER PC9
#define RESET_DRIVER PC8
#define FAULT_DRIVER PC7
#define POLE_PAIRS 14
#define CAN2_TX PB13
#define CAN2_RX PB12
#define CAN1_TX PB9
#define CAN1_RX PB8
#define GM6208_RESISTANCE 31
#define OWN_RESISTANCE 26
#pragma endregion
#if !defined(HAL_CAN_MODULE_ENABLED)
#define HAL_CAN_MODULE_ENABLED
#endif
#include "stm32f4xx_hal.h"
#include "stm32f4xx_hal_can.h"
#include <STM32_CAN.h>

View file

@ -0,0 +1,27 @@
#pragma once
#include "config.h"
#include "STM32_CAN.h"
#include "flash.h"
#include "reg_cah.h"
extern FLASH_RECORD *flash_rec;
extern volatile uint16_t msg_id;
extern volatile uint16_t id_x;
extern volatile uint8_t msg_ch;
extern volatile uint8_t crc_h;
extern volatile uint8_t crc_l;
void send_velocity();
void send_angle();
void send_motor_enabled();
void send_motor_enabled();
void send_id();
void firmware_update();
void send_pid_angle(uint8_t param_pid);
// void send_motor_torque();
void send_pid(uint8_t param_pid);
void setup_id(uint8_t my_id);
void setup_angle(float target_angle);
void setup_pid_angle(uint8_t param_pid, float data);
void listen_can(const CAN_message_t &msg);

View file

@ -0,0 +1,48 @@
#ifndef REG_CAH_H_
#define REG_CAH_H_
#define APP_ADDR 0x0800400 // 16KB - Application
#define ADDR_VAR 0x8040000
#define REG_READ 0x07
#define REG_WRITE 0x08
/* Startup ID device */
#define START_ID 0x00
/* CAN REGISTER ID */
#define REG_ID 0x01
#define REG_BAUDRATE 0x02
#define REG_MOTOR_POSPID_Kp 0x30
#define REG_MOTOR_POSPID_Ki 0x31
#define REG_MOTOR_POSPID_Kd 0x32
#define REG_MOTOR_VELPID_Kp 0x40
#define REG_MOTOR_VELPID_Ki 0x41
#define REG_MOTOR_VELPID_Kd 0x42
#define REG_MOTOR_IMPPID_Kp 0x50
#define REG_MOTOR_IMPPID_Kd 0x51
#define REG_RESET 0x88
#define REG_LED_BLINK 0x8B
#define FOC_STATE 0x60
#define MOTOR_VELOCITY 0x70
#define MOTOR_ENABLED 0x71
#define MOTOR_ANGLE 0x72
#define MOTOR_TORQUE 0x73
#define FIRMWARE_UPDATE 0x55
//For send
#define CAN_MSG_MAX_LEN 7
#define CRC_SIZE 2
#define ID_SIZE sizeof(uint8_t)
#endif // REG_CAH_H_

View file

@ -0,0 +1,44 @@
#include "AS5045.h"
MagneticSensorAS5045::MagneticSensorAS5045(uint16_t as5040_cs, uint16_t as5040_mosi, uint16_t as5040_miso,
uint16_t as5040_sclk): AS5040_CS_(as5040_cs),
AS5040_MOSI_(as5040_mosi),
AS5040_MISO_(as5040_miso),
AS5040_SCLK_(as5040_sclk),
spi(nullptr),
settings(AS5145SSISettings) {
}
MagneticSensorAS5045::~MagneticSensorAS5045() = default;
auto MagneticSensorAS5045::init(SPIClass *_spi) -> void {
this->spi = _spi;
settings = AS5145SSISettings;
pinMode(AS5040_CS_, OUTPUT);
pinMode(AS5040_MISO_, INPUT);
pinMode(AS5040_MOSI_, OUTPUT);
pinMode(AS5040_SCLK_, OUTPUT);
spi->setMISO(AS5040_MISO_);
spi->setMOSI(AS5040_MOSI_);
spi->setSCLK(AS5040_SCLK_);
spi->begin();
this->Sensor::init();
}
float MagneticSensorAS5045::getSensorAngle() {
float angle_data = readRawAngleSSI();
angle_data = (static_cast<float>(angle_data) / AS5045_CPR) * _2PI;
return angle_data;
}
uint16_t MagneticSensorAS5045::readRawAngleSSI() const {
spi->beginTransaction(settings);
digitalWrite(AS5040_CS_, LOW);
uint16_t value = spi->transfer16(0x0000);
digitalWrite(AS5040_CS_, HIGH);
spi->endTransaction();
delayMicroseconds(30);
return (value >> 3) & 0x1FFF; // TODO(vanyabeat): Add error checking MAGNETIC OWERFLOW and etc.
}

View file

@ -0,0 +1,32 @@
#pragma once
#include "SimpleFOC.h"
#include "SPI.h"
#ifndef MSBFIRST
#define MSBFIRST BitOrder::MSBFIRST
#endif
#define AS5045_BITORDER MSBFIRST
#define AS5045_CPR 4096.0f
#define _2PI 6.28318530718f
static SPISettings AS5145SSISettings(1000000, AS5045_BITORDER, SPI_MODE0);
class MagneticSensorAS5045 final: public Sensor {
public:
MagneticSensorAS5045(uint16_t as5040_cs, uint16_t as5040_mosi, uint16_t as5040_miso, uint16_t as5040_sclk);
virtual ~MagneticSensorAS5045();
float getSensorAngle() override;
virtual void init(SPIClass *_spi = &SPI);
[[nodiscard]] uint16_t readRawAngleSSI() const;
private:
uint16_t AS5040_CS_, AS5040_MOSI_, AS5040_MISO_, AS5040_SCLK_;
SPIClass *spi;
SPISettings settings;
};

View file

@ -0,0 +1,10 @@
name=AS5045
version=1.0.1
author=vanyabeat <vanyabeat@protonmail.com>
maintainer=vanyabeat <vanyabeat@protonmail.com>
sentence=Simple library to work with AS5040 and Simple FOC (for Robotroller in Robosemmbler) Fork from https://github.com/runger1101001
paragraph=Simple library to work with AS5040 and Simple FOC and simple library intended for hobby comunity to run the AS5040 magnetic sensor using FOC algorithm. It is intended to support as many BLDC/Stepper motor+sensor+driver combinations as possible and in the same time maintain simplicity of usage. Library supports Arudino devices such as Arduino UNO, MEGA, NANO and similar, stm32 boards such as Nucleo and Bluepill, ESP32 and Teensy boards.
category=Device Control
url=https://docs.simplefoc.com
architectures=*
includes=SimpleFOC.h

View file

@ -0,0 +1,42 @@
#include "DRV8313.h"
DRV8313Driver::DRV8313Driver(int phA, int phB, int phC, int en1, int en2, int en3, int slp, int rst,
int flt) : BLDCDriver3PWM(phA, phB, phC, en1, en2, en3), slp_pin(slp), rst_pin(rst),
flt_pin(flt) {
}
int DRV8313Driver::init() {
// Get state from flt pin
if (_isset(flt_pin)) {
pinMode(flt_pin, INPUT);
if (digitalRead(flt_pin) == HIGH) {
// if the fault pin is high the driver is in fault state
// reset the driver
if (_isset(rst_pin)) {
pinMode(rst_pin, OUTPUT);
digitalWrite(rst_pin, LOW);
delay(1);
digitalWrite(rst_pin, HIGH);
delay(1);
}
}
}
return BLDCDriver3PWM::init();
}
void DRV8313Driver::enable() {
// Enable the driver
if (_isset(slp_pin)) {
pinMode(slp_pin, OUTPUT);
digitalWrite(slp_pin, HIGH);
}
BLDCDriver3PWM::enable();
}
void DRV8313Driver::disable() {
if (_isset(slp_pin)) {
pinMode(slp_pin, OUTPUT);
digitalWrite(slp_pin, LOW);
}
BLDCDriver3PWM::disable();
}

View file

@ -0,0 +1,20 @@
#pragma once
#include "SimpleFOC.h"
class DRV8313Driver : public BLDCDriver3PWM {
public:
DRV8313Driver(int phA, int phB, int phC, int en1 = NOT_SET, int en2 = NOT_SET, int en3 = NOT_SET, int slp = NOT_SET,
int rst = NOT_SET, int flt = NOT_SET);
int init() override;
void enable() override;
void disable() override;
private:
int slp_pin;
int rst_pin;
int flt_pin;
};

View file

@ -0,0 +1,10 @@
name=DRV8313 Simple FOC
version=1.0.0
author=vanyabeat <vanyabeat@protonmail.com>
maintainer=vanyabeat <vanyabeat@protonmail.com>
sentence=Simple library to work with DRV8313 and Simple FOC (for Robotroller in Robosemmbler)
paragraph=Simple library to work with DRV8313 and Simple FOC and simple library intended for hobby comunity to run the BLDC and Stepper motor using FOC algorithm. It is intended to support as many BLDC/Stepper motor+sensor+driver combinations as possible and in the same time maintain simplicity of usage. Library supports Arudino devices such as Arduino UNO, MEGA, NANO and similar, stm32 boards such as Nucleo and Bluepill, ESP32 and Teensy boards.
category=Device Control
url=https://docs.simplefoc.com
architectures=*
includes=SimpleFOC.h

View file

@ -0,0 +1,24 @@
[env:robotroller_reborn]
platform = ststm32
board = genericSTM32F446RE
framework = arduino
upload_protocol = stlink
debug_tool = stlink
monitor_speed = 19200
monitor_parity = N
board_upload.offset_address = 0x08008000
board_build.ldscript = ${PROJECT_DIR}/custom_script.ld
build_flags =
-D STM32F446xx
-D HAL_CAN_MODULE_ENABLED
-D SIMPLEFOC_PWM_LOWSIDE_ACTIVE_HIGH
lib_deps =
askuric/Simple FOC@^2.3.4
pazi88/STM32_CAN@^1.1.2
extra_scripts =
pre:gen_compile_commands.py
post:hex_compile.py

View file

@ -0,0 +1,75 @@
#include "config.h"
void setup_foc(MagneticSensorAS5045 *encoder, BLDCMotor *motor,
DRV8313Driver *driver, LowsideCurrentSense *current_sense,
FLASH_RECORD* pid_data) {
encoder->init(&spi);
/* convert data from flash int value to float*/
conv_float_to_int.i = pid_data[pid_p].value;
float p = conv_float_to_int.f;
conv_float_to_int.i = pid_data[pid_i].value;
float i = conv_float_to_int.f;
conv_float_to_int.i = pid_data[pid_d].value;
float d = conv_float_to_int.f;
// Driver configuration
driver->pwm_frequency = 20000;
driver->voltage_power_supply = 24;
driver->voltage_limit = 24;
driver->init();
// Current sense initialization
current_sense->linkDriver(driver);
current_sense->init();
// Motor configuration
motor->linkSensor(encoder);
motor->linkDriver(driver);
motor->linkCurrentSense(current_sense);
motor->controller = MotionControlType::angle;
motor->torque_controller = TorqueControlType::voltage;
motor->foc_modulation = FOCModulationType::SpaceVectorPWM;
// PID Configuration
motor->PID_velocity.P = 0.5f;
motor->PID_velocity.I = 2.0f;
motor->PID_velocity.D = 0.0f;
motor->LPF_velocity.Tf = 0.01f;
motor->P_angle.P = p;
motor->P_angle.I = i;
motor->P_angle.D = d;
motor->LPF_angle.Tf = 0.02f;
// Motor limits
motor->velocity_limit = 40; // Speed limit in rad/s (382 rpm)
motor->voltage_limit = 24;
motor->current_limit = 0.5;
motor->sensor_direction = Direction::CCW;
motor->init();
motor->initFOC();
}
void foc_step(BLDCMotor *motor) {
if (motor_control_inputs.target_velocity != 0 ||
motor->controller == MotionControlType::velocity) {
if (motor->controller != MotionControlType::velocity) {
motor->controller = MotionControlType::velocity;
}
motor->target = motor_control_inputs.target_velocity;
} else {
if (motor->controller != MotionControlType::angle) {
motor->controller = MotionControlType::angle;
}
motor->target = motor_control_inputs.target_angle;
}
motor->loopFOC();
motor->move();
}

View file

@ -0,0 +1,251 @@
#include "flash.h"
#include <stdbool.h>
#include "hal_conf_extra.h"
void flash_unlock(){
// Check if flash is locked
if(!(FLASH->CR & FLASH_CR_LOCK)) {
return; // Already unlocked
}
// Write flash key sequence to unlock
FLASH->KEYR = 0x45670123; // First key
FLASH->KEYR = 0xCDEF89AB; // Second key
}
void flash_lock() {
if(FLASH->CR & FLASH_CR_LOCK) {
return; // Already locked
}
FLASH->CR |= FLASH_CR_LOCK; // Lock flash memory
}
void erase_sector(uint8_t sector){
// Wait if flash is busy
while(FLASH_BUSY);
// Check if flash is locked and unlock if needed
if(FLASH->CR & FLASH_CR_LOCK) {
flash_unlock();
}
// Set sector erase bit and sector number
FLASH->CR |= FLASH_CR_SER;
FLASH->CR &= ~FLASH_CR_SNB;
FLASH->CR |= (sector << FLASH_CR_SNB_Pos) & FLASH_CR_SNB_Msk;
// Start erase
FLASH->CR |= FLASH_CR_STRT;
// Wait for erase to complete
while(FLASH_BUSY);
// Clear sector erase bit
FLASH->CR &= ~FLASH_CR_SER;
}
void flash_program_word(uint32_t address,uint32_t data,uint32_t byte_len){
// Wait if flash is busy
while(FLASH_BUSY);
// Check if flash is locked and unlock if needed
if(FLASH->CR & FLASH_CR_LOCK) {
flash_unlock();
}
// Set program bit 32bit programm size and Write data to address
if(byte_len == 1) {
FLASH_8BYTE;
FLASH->CR |= FLASH_CR_PG;
*(volatile uint8_t*)address = (uint8_t)data;
} else {
FLASH_32BYTE;
FLASH->CR |= FLASH_CR_PG;
*(volatile uint32_t*)address = data;
}
// Wait for programming to complete
while(FLASH_BUSY);
// Clear program bit
FLASH->CR &= ~FLASH_CR_PG;
}
void flash_write(uint32_t addr, FLASH_RECORD* record){
uint32_t* data = (uint32_t*)record;
uint32_t size = FLASH_RECORD_SIZE / 4; //count words in struct
// Wait if flash is busy
while(FLASH_BUSY);
// Check if flash is locked and unlock if needed
if(FLASH->CR & FLASH_CR_LOCK) {
flash_unlock();
}
// Set program bit and write data to flash
FLASH_32BYTE;
FLASH->CR |= FLASH_CR_PG;
for(int i = 0;i < size;i++){
*(volatile uint32_t*)(addr + (i * 4)) = data[i];
}
// Clear program bit
FLASH->CR &= ~FLASH_CR_PG;
write_ptr = addr + (size * 4); //increase variable storing addr
flash_lock();
}
uint8_t flash_read_word(uint32_t address){
// Check if address is valid
if(address < FLASH_BASE || address > FLASH_END) {
return 0;
}
// Read byte from flash memory
return *((volatile uint8_t*)address);
}
// Wait if flash
// bool validata_crc(FLASH_RECORD* crc){
// return crc->crc == 0x6933? true : false;
// }
uint16_t validate_crc16(uint8_t *data, uint32_t length) {
uint16_t crc = 0xFFFF; // start value for CRC MODBUS
while (length--) {
crc ^= *data++; // XOR
for (uint8_t i = 0; i < 8; i++) {
if (crc & 0x0001) {
crc = (crc >> 1) ^ 0xA001; // polynome 0x8005 (reverse)
} else {
crc >>= 1;
}
}
}
return crc;
}
uint16_t calc_crc_struct(FLASH_RECORD* res){
uint8_t arr_res[FLASH_RECORD_SIZE - 2];
uint16_t crc_res;
/* sorting data without CRC */
arr_res[0] = res->data_id;
arr_res[1] = res->data_type;
/* from 32 to 8 bit */
for(int i = 0;i < 4;i++)
arr_res[i + 2] = (uint8_t)(res->value >> i * 8);
crc_res = validate_crc16(arr_res,FLASH_RECORD_SIZE - 2);
return crc_res;
}
void disable_flash_protection() {
HAL_FLASH_Unlock();
__HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR);
HAL_FLASH_Lock();
}
/* read struct from FLASH */
void flash_read(uint32_t addr,FLASH_RECORD* ptr){
disable_flash_protection();
uint8_t* flash_ptr = (uint8_t*)addr;
uint8_t* dest = (uint8_t*)ptr;
for(int i = 0;i < FLASH_RECORD_SIZE;i++)
dest[i] = flash_ptr[i];
}
void compact_page(){
FLASH_RECORD latest[PARAM_COUNT] = {0};
for(int i = (uint32_t)SECTOR_6;i < (uint32_t)SECTOR_7;i += FLASH_RECORD_SIZE) {
FLASH_RECORD rec;
flash_read(i,&rec);
uint16_t calculated_crc = calc_crc_struct(&rec);
if (calculated_crc == rec.crc && rec.data_id < PARAM_COUNT) {
// if the crc does not match, we check further
latest[rec.data_id] = rec;
}
else
// if
continue;
}
erase_sector(6);
write_ptr = SECTOR_6; // Сброс на начало
for (int i = 0; i < PARAM_COUNT; i++) {
if (latest[i].data_id != 0xFF) {
// alignment
if (write_ptr % 4 != 0) {
write_ptr += (4 - (write_ptr % 4));
}
flash_write(write_ptr, &latest[i]);
}
}
}
void write_param(uint8_t param_id, uint32_t val) {
FLASH_RECORD param_flash;
// __disable_irq(); // Interrupt off
param_flash.data_id = param_id;
param_flash.value = val;
param_flash.data_type = sizeof(uint8_t);
param_flash.crc = calc_crc_struct(&param_flash);
// check alignment
if (write_ptr % 8 != 0) {
write_ptr += (8 - (write_ptr % 8));
}
// check buffer overflow
if (write_ptr + FLASH_RECORD_SIZE >= SECTOR_6_END) {
compact_page(); // after compact_page update
// alignment
if (write_ptr % 8 != 0) {
write_ptr += (8 - (write_ptr % 8));
}
}
flash_write(write_ptr, &param_flash); //inside the function, the write_ptr pointer is automatically incremented by the size of the structure
// __enable_irq(); // Interrupt on
}
FLASH_RECORD* load_params(){
__disable_irq();
static FLASH_RECORD latest[PARAM_COUNT] = {0};
FLASH_RECORD res;
for(uint32_t addr = SECTOR_6;addr < SECTOR_6_END;addr +=FLASH_RECORD_SIZE) {
flash_read(addr,&res);
uint16_t calculated_crc = calc_crc_struct(&res);
if (calculated_crc != res.crc || res.data_id >= PARAM_COUNT) continue;
else{
latest[res.data_id] = res;
write_ptr = addr + FLASH_RECORD_SIZE;
}
}
__enable_irq();
return latest;
}

View file

@ -0,0 +1,115 @@
#include "Arduino.h"
#include "stm32f446xx.h"
#include <SimpleFOC.h>
#include <STM32_CAN.h>
#include <AS5045.h>
#include <DRV8313.h>
#include <cstring>
#include <iostream>
#include <iterator>
#include "common/base_classes/FOCMotor.h"
#include "hal_conf_extra.h"
#include "wiring_analog.h"
#include "wiring_constants.h"
// clang-format on
#include "reg_cah.h"
#include "flash.h"
#include "config.h"
#include "process_can.h"
void SysTick_Handler(void) {
HAL_IncTick();
}
STM32_CAN Can(CAN2, DEF);
/* for FLASH */
uint32_t flash_flag;
uint8_t flag_can = 0;
uint32_t flash_error;
FLASH_EraseInitTypeDef pEraseInit;
uint32_t SectorError;
/* bool for test CAN */
volatile bool CAN_GET = false;
volatile float kt = 0.1; // Torque calculation constant
FLASH_RECORD* flash_rec;
SPIClass spi;
MagneticSensorAS5045 encoder(AS5045_CS, AS5045_MOSI, AS5045_MISO, AS5045_SCLK);
BLDCMotor motor(POLE_PAIRS);
DRV8313Driver driver(TIM1_CH1, TIM1_CH2, TIM1_CH3, EN_W_GATE_DRIVER,
EN_U_GATE_DRIVER, EN_V_GATE_DRIVER, SLEEP_DRIVER,
RESET_DRIVER, FAULT_DRIVER);
LowsideCurrentSense current_sense(0.01, 10.0, CURRENT_SENSOR_1,
CURRENT_SENSOR_2, CURRENT_SENSOR_3);
// Commander command(Serial);
MotorControlInputs motor_control_inputs;
volatile uint16_t msg_id;
volatile uint16_t id_x;
volatile uint8_t msg_ch;
volatile uint8_t crc_h;
volatile uint8_t crc_l;
void setup(){
SCB->VTOR = (volatile uint32_t)0x08008004;
Serial.setRx(HARDWARE_SERIAL_RX_PIN);
Serial.setTx(HARDWARE_SERIAL_TX_PIN);
Serial.begin(115200);
pinMode(PC11, OUTPUT);
pinMode(PC10,OUTPUT);
GPIOC->ODR &= ~GPIO_ODR_OD10;
// Can.enableMBInterrupts();
Can.begin();
Can.setBaudRate(1000000);
// Настройка прерываний CAN
CAN2->IER |= CAN_IER_FMPIE0;
flash_rec = load_params(); //for update write_ptr
if(flash_rec[firmw].value == FIRMWARE_FLAG) NVIC_SystemReset(); //if in flash go to the bootloader
// Initialize FOC system
setup_foc(&encoder, &motor, &driver, &current_sense,flash_rec);
CAN2->IER |= CAN_IER_FMPIE0 | // Сообщение в FIFO0
CAN_IER_FFIE0 | // FIFO0 full
CAN_IER_FOVIE0; // FIFO0 overflow
// Default motor configuration
GPIOC->ODR |= GPIO_ODR_OD11; //set LED
motor.torque_controller = TorqueControlType::foc_current;
motor.controller = MotionControlType::torque;
__enable_irq();
}
void loop() {
__enable_irq();
foc_step(&motor);
CAN_message_t msg;
// Process incoming CAN messages
while (Can.read(msg)) {
listen_can(msg);
CAN_GET = true;
}
/* If receive data from CAN */
if(CAN_GET) {
CAN_GET = false;
}
}

View file

@ -0,0 +1,245 @@
#include "process_can.h"
static CAN_message_t CAN_TX_msg;
static CAN_message_t CAN_inMsg;
template <typename T>
void send_can_with_id_crc(uint8_t id, uint8_t message_type, T* data) {
// Create CAN message
CAN_message_t msg_l;
msg_l.id = id;
// msg_l.len = 8; // Protocol-defined message length
memcpy(&msg_l.buf[0], &message_type, sizeof(uint8_t));
memcpy(&msg_l.buf[1], data, sizeof(T));
// Prepare CRC calculation buffer (ID + data)
uint8_t crc_data[CAN_MSG_MAX_LEN];
// Copy message ID
memcpy(crc_data, (uint8_t*)&msg_l.id, sizeof(T));
// Copy all data bytes
memcpy(crc_data + 1, msg_l.buf, 6);
// Calculate CRC
uint16_t crc_value = validate_crc16(crc_data, CAN_MSG_MAX_LEN);
// Insert CRC into buffer
// memcpy(&msg_l.buf[6], &crc_value, sizeof(uint16_t));
msg_l.buf[6] = crc_value & 0xFF;
msg_l.buf[7] = (crc_value >> 8) & 0xFF;
// Send message
Can.write(msg_l);
}
void send_velocity() {
float current_velocity = motor.shaftVelocity();
if (flash_rec == nullptr) { // Null check
// Error handling: logging, alerts, etc.
return;
}
float value = flash_rec[vel].value;
uint8_t id = flash_rec[addr_id].value;
send_can_with_id_crc(id,'V',&value);
}
void send_angle() {
float current_angle = motor.shaftAngle();
if (flash_rec == nullptr) { // Null check
// Error handling: logging, alerts, etc.
return;
}
uint8_t id = flash_rec[addr_id].value;
send_can_with_id_crc(id,'A',&current_angle);
}
void send_motor_enabled() {
/* Firmware data reading */
if (flash_rec == nullptr) { // Null check
// Error handling: logging, alerts, etc.
return;
}
uint8_t value = motor_control_inputs.motor_enabled; //copy current motor state
uint8_t id = flash_rec[addr_id].value;
send_can_with_id_crc(id,'M',&value);
}
void send_id() {
/* Firmware data reading */
if (flash_rec == nullptr) { // Null check
// Error handling: logging, alerts, etc.
return;
}
uint8_t id = flash_rec[addr_id].value;
send_can_with_id_crc(id,'I',&id);
}
// void send_motor_torque() {
// float i_q = motor.current.q; // Q-axis current (A)
// float torque = kt * i_q; // Torque calculation
// torque *= 100;
// CAN_TX_msg.id = flash_rec->value;
// CAN_TX_msg.buf[0] = 'T';
// CAN_TX_msg.len = 5;
// memcpy(&CAN_TX_msg.buf[1], &torque, sizeof(torque));
// Can.write(CAN_TX_msg);
// }
void send_pid_angle(uint8_t param_pid){
if (flash_rec == nullptr) { // Null check
return;
}
uint8_t id = flash_rec[addr_id].value;
conv_float_to_int.i = flash_rec[param_pid].value;
uint32_t data = conv_float_to_int.i;
switch(param_pid){
case pid_p:
param_pid = REG_MOTOR_POSPID_Kp;
break;
case pid_i:
param_pid = REG_MOTOR_POSPID_Ki;
break;
case pid_d:
param_pid = REG_MOTOR_POSPID_Kd;
break;
}
send_can_with_id_crc(id,param_pid,&data);
}
void setup_id(uint8_t my_id) {
write_param(addr_id,my_id);
}
void firmware_update(){
write_param(firmw,FIRMWARE_FLAG);
NVIC_SystemReset();
}
void setup_angle(float target_angle) {
motor.enable(); // Enable motor if disabled
// motor.controller = MotionControlType::angle;
motor_control_inputs.target_angle = target_angle;
// motor.move(target_angle);
}
// void setup_pid_angle(uint8_t param_pid, uint32_t data){
// conv_float_to_int.f = data;
// switch (param_pid) {
// case pid_p:
// motor.P_angle.P = conv_float_to_int.f;
// break;
// case pid_i:
// motor.P_angle.I = conv_float_to_int.f;
// break;
// case pid_d:
// motor.P_angle.D = conv_float_to_int.f;
// break;
// default:
// break;
// }
// write_param(param_pid,data);
// }
void listen_can(const CAN_message_t &msg) {
msg_id = msg.id;
msg_ch = msg_id & 0xF; // Extract message channel
uint16_t id_x = (msg_id >> 4) & 0x7FF; // Extract device address
/* CRC Calculation */
uint16_t received_crc = (msg.buf[msg.len - 2]) | (msg.buf[msg.len - 1] << 8);
uint8_t data[10] = {0}; // Message buffer for CRC verification
// Copy message ID (2 bytes)
memcpy(data, (uint8_t*)&msg_id, sizeof(msg_id));
// Copy message data (excluding CRC bytes)
memcpy(data + sizeof(msg_id), msg.buf, msg.len - 2);
// Calculate CRC
uint16_t calculated_crc = validate_crc16(data, sizeof(msg_id) + msg.len - 2);
// Verify CRC match
if (calculated_crc != received_crc) {
return; // Ignore message on CRC mismatch
}
flash_rec = load_params();
/* Message Structure: 0x691
69 - Device address
1 - Action code */
if(id_x == flash_rec[addr_id].value){
if(msg_ch == REG_WRITE){
switch(msg.buf[0]) {
case REG_ID:
setup_id(msg.buf[1]);
break;
case REG_LED_BLINK:
for (int i = 0; i < 10; i++) {
GPIOC->ODR ^= GPIO_ODR_OD10;
delay(100);
}
break;
case MOTOR_ANGLE:
memcpy(&motor_control_inputs.target_angle, &msg.buf[1],
sizeof(motor_control_inputs.target_angle));
setup_angle(motor_control_inputs.target_angle);
break;
case REG_MOTOR_POSPID_Kp:
memcpy(&motor.P_angle.P, &msg.buf[1], sizeof(float));
conv_float_to_int.f = motor.P_angle.P;
write_param(pid_p,conv_float_to_int.i);
break;
case REG_MOTOR_POSPID_Ki:
memcpy(&motor.P_angle.I, &msg.buf[1], sizeof(float));
conv_float_to_int.f = motor.P_angle.I;
write_param(pid_i,conv_float_to_int.i);
break;
case REG_MOTOR_POSPID_Kd:
memcpy(&motor.P_angle.D, &msg.buf[1], sizeof(float));
conv_float_to_int.f = motor.P_angle.D;
write_param(pid_d,conv_float_to_int.i);
break;
case FIRMWARE_UPDATE:
firmware_update();
break;
case MOTOR_ENABLED:
if (msg.buf[1] == 1) {
motor.enable();
motor_control_inputs.motor_enabled = 1;
} else {
motor.disable();
motor_control_inputs.motor_enabled = 0;
}
default:
break;
}
}
else if (msg_ch == REG_READ) {
switch (msg.buf[0]) {
case REG_ID: send_id(); break;
case MOTOR_VELOCITY: send_velocity(); break;
case MOTOR_ANGLE: send_angle(); break;
case MOTOR_ENABLED: send_motor_enabled(); break;
// case MOTOR_TORQUE: send_motor_torque(); break;
// case FOC_STATE: send_foc_state(); break;
case REG_MOTOR_POSPID_Kp: send_pid_angle(pid_p); break;
case REG_MOTOR_POSPID_Ki: send_pid_angle(pid_i); break;
case REG_MOTOR_POSPID_Kd: send_pid_angle(pid_d); break;
default: break;
}
}
}
}

View file

@ -0,0 +1,86 @@
# CAN Communication Scripts
This repository contains Python scripts for testing and interacting with a CAN bus system. These scripts enable sending and receiving CAN messages to control a motor, set angles, and adjust velocities.
## Prerequisites
1. **Python 3.7+** installed on your system.
2. **`python-can` library** installed. Install it via pip:
```bash
pip install python-can
```
3. **SocketCAN interface** properly configured on your Linux system. The default channel is `can0`.
## Usage
### 1. Receiving CAN Messages
The script `python_can.py` listens to the CAN bus and processes incoming messages.
#### Run:
```bash
python3 python_can.py
```
#### Features:
- Processes messages with data length 5.
- Parses the first byte (`flag`) to determine the type:
- `'A'`: Angle (float).
- `'V'`: Velocity (float).
- `'E'`: Enable/disable status (boolean).
### 2. Enabling or Disabling the Motor
The script `python_enable_motor.py` sends commands to enable or disable the motor.
#### Run:
```bash
python3 python_enable_motor.py <0|1>
```
#### Arguments:
- `0`: Disable the motor.
- `1`: Enable the motor.
### 3. Sending Target Angle
The script `python_send_angle.py` sends a target angle to the CAN bus.
#### Run:
```bash
python3 python_send_angle.py
```
#### Behavior:
- Sends a message with a predefined target angle every second.
- Adjust the target angle in the script (`target_angle` variable).
### 4. Sending Target Velocity
The script `python_send_velocity.py` sends a target velocity to the CAN bus.
#### Run:
```bash
python3 python_send_velocity.py
```
#### Behavior:
- Sends a message with a predefined target velocity every second.
- Adjust the target velocity in the script (`target_speed` variable).
## Configuration
### CAN Interface
The scripts use the following default CAN bus settings:
- **Channel**: `can0`
- **Bitrate**: `1 Mbps`
If your configuration differs, update the `Bus()` initialization in the scripts.
## Troubleshooting
1. **"Error initializing CAN bus"**:
- Ensure your CAN interface is correctly configured and active:
```bash
sudo ip link set can0 up type can bitrate 1000000
```

View file

@ -0,0 +1,54 @@
import can
import sys
# Function to send the motor enable/disable command
def send_motor_enable(bus, enable):
"""
Sends a command to enable or disable the motor.
:param bus: The CAN bus
:param enable: 1 to enable the motor, 0 to disable it
"""
msg = can.Message()
msg.arbitration_id = 1 # Message ID
msg.is_extended_id = False
msg.dlc = 2 # Message length (flag + 1 byte of data)
msg.data = [ord('E'), enable] # 'E' for the command, followed by 0 or 1
try:
bus.send(msg)
state = "enabled" if enable else "disabled"
print(f"Sent message to {state} motor")
print(f"Message data: {msg.data}")
except can.CanError as e:
print(f"Message failed to send: {e}")
sys.exit(1) # Exit the program on failure
def main():
# CAN interface setup
bus = None # Define outside the try block for proper shutdown
try:
bus = can.interface.Bus(channel='can0', bustype='socketcan', bitrate=1000000) # Ensure the bitrate matches the microcontroller settings
print("CAN bus initialized.")
# Ensure the state is passed via arguments
if len(sys.argv) != 2 or sys.argv[1] not in ['0', '1']:
print("Usage: python3 script_name.py <0|1>")
print("0 - Disable motor, 1 - Enable motor")
sys.exit(1)
enable = int(sys.argv[1])
send_motor_enable(bus, enable)
except Exception as e:
print(f"Error initializing CAN bus: {e}")
sys.exit(1)
finally:
# Ensure the bus is properly shut down
if bus is not None:
bus.shutdown()
print("CAN bus shut down.")
if __name__ == '__main__':
main()

View file

@ -0,0 +1,141 @@
import can
import sys
import time
from intelhex import IntelHex
# Конфигурация
CAN_CHANNEL = 'socketcan'
CAN_INTERFACE = 'can0'
CAN_BITRATE = 1000000
#ch =int(input("Введите id устройства:"))
ch = int(sys.argv[2])
BOOT_CAN_ID = (ch * 16) + 1
DATA_CAN_ID = (ch * 16) + 3
BOOT_CAN_END = (ch * 16) + 2
ACK_CAN_ID = 0x05
#конфиг для crc16 ibm
def debug_print(msg):
print(f"[DEBUG] {msg}")
def calculate_crc16(data: bytes) -> int:
crc = 0xFFFF
for byte in data:
crc ^= byte
for _ in range(8):
if crc & 0x0001:
crc = (crc >> 1) ^ 0xA001
else:
crc >>= 1
return crc
def send_firmware(hex_file):
try:
debug_print("Инициализация CAN...")
bus = can.interface.Bus(
channel=CAN_INTERFACE,
bustype=CAN_CHANNEL,
bitrate=CAN_BITRATE
)
debug_print("Чтение HEX-файла...")
ih = IntelHex(hex_file)
binary_data = ih.tobinstr() # Исправлено на tobinstr()
fw_size = len(binary_data)
debug_print(f"Размер прошивки: {fw_size} байт")
# Расчет CRC
debug_print("Расчёт CRC...")
# calculator = Calculator(Crc16.IBM)
fw_crc = calculate_crc16(binary_data)
debug_print(f"CRC: 0x{fw_crc:04X}")
# Отправка START
start_data = bytearray([0x01])
start_data += fw_size.to_bytes(4, 'little')
start_data += fw_crc.to_bytes(2, 'little')
debug_print(f"START: {list(start_data)}")
start_msg = can.Message(
arbitration_id=BOOT_CAN_ID,
data=bytes(start_data),
is_extended_id=False
)
try:
bus.send(start_msg)
except can.CanError as e:
debug_print(f"Ошибка отправки START: {str(e)}")
return
# Ожидание ACK
debug_print("Ожидание ACK...")
ack = wait_for_ack(bus)
if not ack:
debug_print("Таймаут ACK START")
return
debug_print(f"Получен ACK: {list(ack.data)}")
# Отправка данных
packet_size = 8
for i in range(0, len(binary_data), packet_size):
chunk = binary_data[i:i+packet_size]
# Дополнение до 8 байт
if len(chunk) < 8:
chunk += b'\xFF' * (8 - len(chunk))
debug_print(f"Пакет {i//8}: {list(chunk)}")
data_msg = can.Message(
arbitration_id=DATA_CAN_ID,
data=chunk,
is_extended_id=False
)
try:
bus.send(data_msg)
except can.CanError as e:
debug_print(f"Ошибка отправки данных: {str(e)}")
return
ack = wait_for_ack(bus)
if not ack:
debug_print("Таймаут ACK DATA")
return
# Финал
debug_print("Отправка FINISH...")
finish_msg = can.Message(
arbitration_id=BOOT_CAN_END,
data=bytes([0xAA]),
is_extended_id=False
)
bus.send(finish_msg)
ack = wait_for_ack(bus, timeout=1.0)
if ack and ack.data[0] == 0xAA:
debug_print("Прошивка подтверждена!")
else:
debug_print("Ошибка верификации!")
except Exception as e:
debug_print(f"Критическая ошибка: {str(e)}")
finally:
bus.shutdown()
def wait_for_ack(bus, timeout=1.0):
start_time = time.time()
while time.time() - start_time < timeout:
msg = bus.recv(timeout=0.1) # Неблокирующий режим
if msg and msg.arbitration_id == ACK_CAN_ID:
return msg
return None
if __name__ == "__main__":
import sys
if len(sys.argv) != 3:
print("Использование: sudo python3 can_flasher.py firmware.hex")
sys.exit(1)
send_firmware(sys.argv[1])

View file

@ -0,0 +1,70 @@
import can
import time
import sys
# Конфигурация
CAN_INTERFACE = 'can0'
OLD_DEVICE_ID = int(sys.argv[1]) # Текущий ID устройства (по умолчанию)
REG_WRITE = 0x8 # Код команды чтения
REG_ID = 0x55 # Адрес регистра с Firmware Update
def send_can_message(bus, can_id, data):
"""Отправка CAN-сообщения"""
try:
msg = can.Message(
arbitration_id=can_id,
data=data,
is_extended_id=False
)
bus.send(msg)
print(f"[Отправка] CAN ID: 0x{can_id:03X}, Данные: {list(data)}")
return True
except can.CanError as e:
print(f"Ошибка CAN: {e}")
return False
def validate_crc16(data):
"""Расчет CRC16 (MODBUS) для проверки целостности данных"""
crc = 0xFFFF
for byte in data:
crc ^= byte
for _ in range(8):
if crc & 0x0001:
crc = (crc >> 1) ^ 0xA001
else:
crc >>= 1
return crc
# Инициализация CAN-интерфейса
bus = can.interface.Bus(channel=CAN_INTERFACE, bustype='socketcan')
# ======= 1. Запрос текущего ID устройства =======
# Формируем CAN ID для чтения: (OLD_DEVICE_ID << 4) | REG_READ
can_id_read = (OLD_DEVICE_ID << 4) | REG_WRITE
# Данные для запроса: [регистр, резервный байт]
data_read = [REG_ID, 0x00]
# Формируем полные данные для расчета CRC:
# - CAN ID разбивается на 2 байта (little-endian)
# - Добавляем данные запроса
full_data_for_crc = list(can_id_read.to_bytes(2, 'little')) + data_read
# Рассчитываем CRC и разбиваем на байты (little-endian)
crc = validate_crc16(full_data_for_crc)
crc_bytes = list(crc.to_bytes(2, 'little'))
# Собираем итоговый пакет: данные + CRC
packet_read = data_read + crc_bytes
print("Переход в boot режим", packet_read)
send_can_message(bus, can_id_read, packet_read)
bus.shutdown()
if __name__ == "__main__":
import sys
if len(sys.argv) != 2:
print("Использование: python3 firmware_test.py address")
sys.exit(1)

View file

@ -0,0 +1,103 @@
import can
import time
import struct
# Конфигурация
CAN_INTERFACE = 'can0'
OLD_DEVICE_ID = 0x00 # Текущий ID устройства (по умолчанию)
REG_READ = 0x7 # Код команды чтения
REG_ID = 0x30 # Адрес регистра с REG_PMOTOR_POSPID_Kp устройства
def send_can_message(bus, can_id, data):
"""Отправка CAN-сообщения"""
try:
msg = can.Message(
arbitration_id=can_id,
data=data,
is_extended_id=False
)
bus.send(msg)
print(f"[Отправка] CAN ID: 0x{can_id:03X}, Данные: {list(data)}")
return True
except can.CanError as e:
print(f"Ошибка CAN: {e}")
return False
def receive_response(bus, timeout=1.0):
"""Ожидание ответа от устройства"""
start_time = time.time()
while time.time() - start_time < timeout:
msg = bus.recv(timeout=0.1)
if msg:
print(f"[Прием] CAN ID: 0x{msg.arbitration_id:03X}, Данные: {list(msg.data)}")
return msg
print("[Ошибка] Таймаут")
return None
def validate_crc16(data):
"""Расчет CRC16 (MODBUS) для проверки целостности данных"""
crc = 0xFFFF
for byte in data:
crc ^= byte
for _ in range(8):
if crc & 0x0001:
crc = (crc >> 1) ^ 0xA001
else:
crc >>= 1
return crc
# Инициализация CAN-интерфейса
bus = can.interface.Bus(channel=CAN_INTERFACE, bustype='socketcan')
# ======= 1. Запрос текущего ID устройства =======
# Формируем CAN ID для чтения: (OLD_DEVICE_ID << 4) | REG_READ
can_id_read = (OLD_DEVICE_ID << 4) | REG_READ
# Данные для запроса: [регистр, резервный байт]
data_read = [REG_ID, 0x00]
# Формируем полные данные для расчета CRC:
# - CAN ID разбивается на 2 байта (little-endian)
# - Добавляем данные запроса
full_data_for_crc = list(can_id_read.to_bytes(2, 'little')) + data_read
# Рассчитываем CRC и разбиваем на байты (little-endian)
crc = validate_crc16(full_data_for_crc)
crc_bytes = list(crc.to_bytes(2, 'little'))
# Собираем итоговый пакет: данные + CRC
packet_read = data_read + crc_bytes
print("Запрос на чтение ID:", packet_read)
send_can_message(bus, can_id_read, packet_read)
# ======= 2. Получение и проверка ответа =======
response = receive_response(bus)
if response:
data = response.data
if len(data) < 4:
print("Слишком короткий ответ")
# Проверяем минимальную длину ответа (данные + CRC)
else:
id_bytes = response.arbitration_id.to_bytes(1,byteorder='little')
#buff with id and data without CRC
full_data = list(id_bytes) + list(data[:-2])
print(f"Received full_data: {list(full_data)}")
received_crc = int.from_bytes(data[-2:], byteorder='little')
#calc CRC
calc_crc = validate_crc16(full_data)
print(f"Расчитанный CRC PYTHON : 0x{calc_crc:02X}")
if received_crc == calc_crc:
# Если CRC совпадает, проверяем структуру ответа:
kp_value = struct.unpack('<f', bytes(data[1:5]))[0]
print(f"Текущий Kp устройства: {kp_value:.3f}")
else:
print("Ошибка: CRC не совпадает")
else:
print("Устройство не ответило")
# Завершаем работу с шиной
bus.shutdown()

View file

@ -0,0 +1,115 @@
import can
import time
# Конфигурация
CAN_INTERFACE = 'can0'
OLD_DEVICE_ID = 0x00
NEW_DEVICE_ID = 0x69
REG_WRITE = 0x8
REG_READ = 0x7
REG_ID = 0x1
def send_can_message(bus, can_id, data):
"""Отправка CAN-сообщения"""
try:
msg = can.Message(
arbitration_id=can_id,
data=data,
is_extended_id=False
)
bus.send(msg)
print(f"[Отправка] CAN ID: 0x{can_id:03X}, Данные: {list(data)}")
return True
except can.CanError as e:
print(f"Ошибка CAN: {e}")
return False
def receive_response(bus, timeout=2.0):
"""Ожидание ответа"""
start_time = time.time()
while time.time() - start_time < timeout:
msg = bus.recv(timeout=0.1)
if msg:
print(f"[Прием] CAN ID: 0x{msg.arbitration_id:03X}, Данные: {list(msg.data)}")
return msg
print("[Ошибка] Таймаут")
return None
def validate_crc16(data):
"""Функция расчета CRC16 (MODBUS)"""
crc = 0xFFFF
for byte in data:
crc ^= byte
for _ in range(8):
if crc & 0x0001:
crc = (crc >> 1) ^ 0xA001
else:
crc >>= 1
return crc
# Инициализация
bus = can.interface.Bus(channel=CAN_INTERFACE, bustype='socketcan')
# ======= 1. Отправляем команду изменить ID =======
# Весь буфер: id + команда + параметры
OLD_WITH_REG = (OLD_DEVICE_ID << 4) | REG_WRITE
id_bytes = list(OLD_WITH_REG.to_bytes(2, byteorder='little'))
# Важные части сообщения: address (id), команда, параметры
data_write = [REG_ID, NEW_DEVICE_ID] # команда изменить ID
# Полностью собираем массив для CRC (включая id и команду)
full_data_for_crc = id_bytes + data_write
# Расчет CRC по всему пакету
crc = validate_crc16(full_data_for_crc)
crc_bytes = list(crc.to_bytes(2, byteorder='little'))
# Итоговый пакет: команда + параметры + CRC
packet_write = data_write + crc_bytes
print("Отправляем: команда изменить ID + CRC:", packet_write)
# Отправляем с `OLD_DEVICE_ID` в качестве адреса
send_can_message(bus, (OLD_DEVICE_ID << 4) | REG_WRITE, packet_write)
time.sleep(0.5)
# ======= 2. Запрашиваем текущий ID (используем новый адрес) =======
# Теперь для запроса используем **уже новый id**
NEW_WITH_REG = (NEW_DEVICE_ID << 4) | REG_READ
current_id_bytes = list(NEW_WITH_REG.to_bytes(2, byteorder='little'))
data_read = [REG_ID, 0x00]
full_data_for_crc = current_id_bytes + data_read
crc = validate_crc16(full_data_for_crc)
crc_bytes = list(crc.to_bytes(2, byteorder='little'))
packet_read = data_read + crc_bytes
print("Запрос на чтение ID + CRC (после смены):", packet_read)
send_can_message(bus, (NEW_DEVICE_ID << 4) | REG_READ, packet_read)
# ======= 3. Получение и проверка ответа =======
response = receive_response(bus)
if response:
data = response.data
if len(data) < 4:
print("Ответ слишком короткий")
else:
received_crc = int.from_bytes(data[-2:], byteorder='little')
print("Полученный CRC: ", received_crc)
# Расчет CRC по всему пакету без CRC
calc_crc = validate_crc16(data[:-2])
if received_crc == calc_crc:
if data[0] == ord('I') and data[1] == NEW_DEVICE_ID:
print(f"\nУСПЕХ! ID устройства изменен на 0x{NEW_DEVICE_ID:02X}")
else:
print(f"Некорректный ответ: {list(data)}")
else:
print("CRC не совпадает, данные повреждены.")
else:
print("Нет ответа от устройства.")
bus.shutdown()

View file

@ -0,0 +1,126 @@
import can
import time
import struct
import sys
# Конфигурация
CAN_INTERFACE = 'can0'
DEVICE_ID = int(sys.argv[1]) # ID ADDR for servo
REG_READ = 0x7 # Код команды чтения
REG_MOTOR_POSPID_Kp = 0x30
REG_MOTOR_POSPID_Ki = 0x31
REG_MOTOR_POSPID_Kd = 0x32
def send_can_message(bus, can_id, data):
"""Отправка CAN-сообщения"""
try:
msg = can.Message(
arbitration_id=can_id,
data=data,
is_extended_id=False
)
bus.send(msg)
print(f"[Отправка] CAN ID: 0x{can_id:03X}, Данные: {list(data)}")
return True
except can.CanError as e:
print(f"Ошибка CAN: {e}")
return False
def validate_crc16(data):
"""Расчет CRC16 (MODBUS)"""
crc = 0xFFFF
for byte in data:
crc ^= byte
for _ in range(8):
if crc & 0x0001:
crc = (crc >> 1) ^ 0xA001
else:
crc >>= 1
return crc
def send_read_request(bus, device_id, register):
"""Отправка запроса на чтение регистра"""
can_id = (device_id << 4) | REG_READ
data_part = [register, 0x00]
# Расчет CRC для CAN ID (2 байта) + данные
full_data_for_crc = list(can_id.to_bytes(2, 'little')) + data_part
crc = validate_crc16(full_data_for_crc)
crc_bytes = list(crc.to_bytes(2, 'little'))
# Формирование итогового пакета
packet = data_part + crc_bytes
send_can_message(bus, can_id, packet)
def receive_pid_response(bus, timeout=1.0):
"""Получение и проверка ответа с PID-значением"""
start_time = time.time()
while time.time() - start_time < timeout:
msg = bus.recv(timeout=0.1)
if msg and msg.arbitration_id == DEVICE_ID:
print(f"[Прием] CAN ID: 0x{msg.arbitration_id:03X}, Данные: {list(msg.data)}")
if len(msg.data) < 8:
print("Ошибка: Слишком короткий ответ")
return None
# Извлечение данных и CRC
data = msg.data
received_crc = int.from_bytes(data[-2:], byteorder='little')
# Подготовка данных для проверки CRC
id_bytes = msg.arbitration_id.to_bytes(1, 'little')
full_data = list(id_bytes) + list(data[:-2])
# Проверка CRC
calc_crc = validate_crc16(full_data)
if calc_crc != received_crc:
print(f"Ошибка CRC: ожидалось 0x{calc_crc:04X}, получено 0x{received_crc:04X}")
return None
# Извлечение float значения
try:
value = struct.unpack('<f', bytes(data[1:5]))[0]
return value
except struct.error:
print("Ошибка распаковки float")
return None
print("Таймаут ожидания ответа")
return None
def main():
"""Основная логика чтения PID-коэффициентов"""
bus = can.interface.Bus(channel=CAN_INTERFACE, bustype='socketcan')
try:
# Чтение коэффициентов с задержкой
print("\nЧтение Kp...")
send_read_request(bus, DEVICE_ID, REG_MOTOR_POSPID_Kp)
kp = receive_pid_response(bus)
if kp is not None:
print(f"Текущий Kp: {kp:.3f}")
time.sleep(1)
print("\nЧтение Ki...")
send_read_request(bus, DEVICE_ID, REG_MOTOR_POSPID_Ki)
ki = receive_pid_response(bus)
if ki is not None:
print(f"Текущий Ki: {ki:.3f}")
time.sleep(1)
print("\nЧтение Kd...")
send_read_request(bus, DEVICE_ID, REG_MOTOR_POSPID_Kd)
kd = receive_pid_response(bus)
if kd is not None:
print(f"Текущий Kd: {kd:.3f}")
finally:
bus.shutdown()
if __name__ == "__main__":
if len(sys.argv) != 2:
print("Используйте python3 read_pid.py addr")
sys.exit(1)
main()

View file

@ -0,0 +1,98 @@
import can
import struct
import time
import argparse
# Константы
CAN_INTERFACE = 'can0'
DEVICE_ID = 0x27 # ID ADDR for servo
REG_WRITE = 0x7
REG_POS = 0x72 # MOTOR+ANGLE = 0x72
def validate_crc16(data):
# Calculate CRC16
crc = 0xFFFF
for byte in data:
crc ^= byte
for _ in range(8):
if crc & 0x0001:
crc = (crc >> 1) ^ 0xA001
else:
crc >>= 1
return crc
def receive_response(bus, timeout=1.0):
"""Ожидание ответа от устройства"""
start_time = time.time()
while time.time() - start_time < timeout:
msg = bus.recv(timeout=0.1)
if msg:
print(f"[Прием] CAN ID: 0x{msg.arbitration_id:03X}, Данные: {list(msg.data)}")
return msg
print("[Ошибка] Таймаут")
return None
def send_target_angle(bus):
# ID and cmd
arbitration_id = (DEVICE_ID << 4) | REG_WRITE
id_bytes = list(arbitration_id.to_bytes(2, byteorder='little'))
# cmd + parametrs
data_write = [REG_POS]
full_data_for_crc = id_bytes + data_write
crc = validate_crc16(full_data_for_crc)
crc_bytes = list(crc.to_bytes(2, byteorder='little'))
# Full packet
packet = data_write + crc_bytes
msg = can.Message(
arbitration_id=arbitration_id,
is_extended_id=False,
data=packet
)
bus.send(msg)
response = receive_response(bus)
if response:
data = response.data
if len(data) < 4:
print("Слишком короткий ответ")
# Проверяем минимальную длину ответа (данные + CRC)
else:
id_bytes = response.arbitration_id.to_bytes(1,byteorder='little')
#buff with id and data without CRC
full_data = list(id_bytes) + list(data[:-2])
print(f"Received full_data: {list(full_data)}")
received_crc = int.from_bytes(data[-2:], byteorder='little')
#calc CRC
calc_crc = validate_crc16(full_data)
print(f"Расчитанный CRC PYTHON : 0x{calc_crc:02X}")
if received_crc == calc_crc:
# Если CRC совпадает, проверяем структуру ответа:
velocity = struct.unpack('<f', bytes(data[1:5]))[0]
print(f"Угол: {velocity}")
else:
print("Ошибка: CRC не совпадает")
else:
print("Устройство не ответило")
def main():
# Инициализация CAN
bus = can.interface.Bus(channel=CAN_INTERFACE, bustype='socketcan')
print("CAN шина инициализирована.")
send_target_angle(bus)
bus.shutdown()
if __name__ == '__main__':
main()

View file

@ -0,0 +1,108 @@
import can
import time
import sys
# Конфигурация
CAN_INTERFACE = 'can0'
OLD_DEVICE_ID = int(sys.argv[1]) # Текущий ID устройства (по умолчанию)
REG_READ = 0x7 # Код команды чтения
REG_ID = 0x01 # Адрес регистра с ID устройства
def send_can_message(bus, can_id, data):
"""Отправка CAN-сообщения"""
try:
msg = can.Message(
arbitration_id=can_id,
data=data,
is_extended_id=False
)
bus.send(msg)
print(f"[Отправка] CAN ID: 0x{can_id:03X}, Данные: {list(data)}")
return True
except can.CanError as e:
print(f"Ошибка CAN: {e}")
return False
def receive_response(bus, timeout=1.0):
"""Ожидание ответа от устройства"""
start_time = time.time()
while time.time() - start_time < timeout:
msg = bus.recv(timeout=0.1)
if msg:
print(f"[Прием] CAN ID: 0x{msg.arbitration_id:03X}, Данные: {list(msg.data)}")
return msg
print("[Ошибка] Таймаут")
return None
def validate_crc16(data):
"""Расчет CRC16 (MODBUS) для проверки целостности данных"""
crc = 0xFFFF
for byte in data:
crc ^= byte
for _ in range(8):
if crc & 0x0001:
crc = (crc >> 1) ^ 0xA001
else:
crc >>= 1
return crc
# Инициализация CAN-интерфейса
bus = can.interface.Bus(channel=CAN_INTERFACE, bustype='socketcan')
# ======= 1. Запрос текущего ID устройства =======
# Формируем CAN ID для чтения: (OLD_DEVICE_ID << 4) | REG_READ
can_id_read = (OLD_DEVICE_ID << 4) | REG_READ
# Данные для запроса: [регистр, резервный байт]
data_read = [REG_ID, 0x00]
# Формируем полные данные для расчета CRC:
# - CAN ID разбивается на 2 байта (little-endian)
# - Добавляем данные запроса
full_data_for_crc = list(can_id_read.to_bytes(2, 'little')) + data_read
# Рассчитываем CRC и разбиваем на байты (little-endian)
crc = validate_crc16(full_data_for_crc)
crc_bytes = list(crc.to_bytes(2, 'little'))
# Собираем итоговый пакет: данные + CRC
packet_read = data_read + crc_bytes
print("Запрос на чтение ID:", packet_read)
send_can_message(bus, can_id_read, packet_read)
# ======= 2. Получение и проверка ответа =======
response = receive_response(bus)
if response:
data = response.data
if len(data) < 4:
print("Слишком короткий ответ")
# Проверяем минимальную длину ответа (данные + CRC)
else:
id_bytes = response.arbitration_id.to_bytes(1,byteorder='little')
#buff with id and data without CRC
full_data = list(id_bytes) + list(data[:-2])
print(f"Received full_data: {list(full_data)}")
received_crc = int.from_bytes(data[-2:], byteorder='little')
#calc CRC
calc_crc = validate_crc16(full_data)
print(f"Расчитанный CRC PYTHON : 0x{calc_crc:02X}")
if received_crc == calc_crc:
# Если CRC совпадает, проверяем структуру ответа:
print(f"Текущий ID устройства: 0x{data[1]:02X}")
else:
print("Ошибка: CRC не совпадает")
else:
print("Устройство не ответило")
# Завершаем работу с шиной
bus.shutdown()
if __name__ == "__main__":
import sys
if len(sys.argv) != 2:
print("Использование: python3 can_flasher.py address")
sys.exit(1)

View file

@ -0,0 +1,67 @@
from can.interface import Bus
import can
import struct
import time
import argparse
# Константы
CAN_INTERFACE = 'can0'
DEVICE_ID = 0x27 # ID ADDR for servo
REG_WRITE = 0x8
REG_POS = 0x72 # MOTOR+ANGLE = 0x72
def validate_crc16(data):
# Calculate CRC16
crc = 0xFFFF
for byte in data:
crc ^= byte
for _ in range(8):
if crc & 0x0001:
crc = (crc >> 1) ^ 0xA001
else:
crc >>= 1
return crc
def send_target_angle(bus, target_angle):
# ID and cmd
arbitration_id = (DEVICE_ID << 4) | REG_WRITE
id_bytes = list(arbitration_id.to_bytes(2, byteorder='little'))
# cmd + parametrs
data_write = [REG_POS] + list(struct.pack('<f', target_angle))
full_data_for_crc = id_bytes + data_write
crc = validate_crc16(full_data_for_crc)
crc_bytes = list(crc.to_bytes(2, byteorder='little'))
# Full packet
packet = data_write + crc_bytes
msg = can.Message(
arbitration_id=arbitration_id,
is_extended_id=False,
data=packet
)
try:
bus.send(msg)
print(f"[Отправка] CAN ID: 0x{arbitration_id:03X}, Угол: {target_angle} rad, Данные: {list(msg.data)}")
except can.CanError:
print("Ошибка отправки сообщения")
def main():
parser = argparse.ArgumentParser(description="Отправка угла позиции по CAN.")
parser.add_argument("--angle", type=float, required=True, help="Угол (в градусах)")
args = parser.parse_args()
# Инициализация CAN
bus = Bus(channel=CAN_INTERFACE, bustype='socketcan')
print("CAN шина инициализирована.")
send_target_angle(bus, args.angle)
bus.shutdown()
if __name__ == '__main__':
main()

View file

@ -0,0 +1,76 @@
import can
import struct
import time
import sys
# Function to send the target speed
def send_target_speed(bus, target_speed):
msg = can.Message()
msg.arbitration_id = 1 # Message ID
msg.is_extended_id = False
msg.dlc = 5 # Message length
msg.data = bytearray([ord('V')] + list(struct.pack('<f', target_speed))) # 'V' for the command identifier, followed by the speed in float format
try:
bus.send(msg)
print(f"Sent message with target speed: {target_speed} rad/s")
except can.CanError:
print("Message failed to send")
# Function to send the motor enable/disable command
def send_motor_enable(bus, enable):
"""
Sends a command to enable or disable the motor.
:param bus: The CAN bus
:param enable: 1 to enable the motor, 0 to disable it
"""
msg = can.Message()
msg.arbitration_id = 1 # Message ID
msg.is_extended_id = False
msg.dlc = 2 # Message length (flag + 1 byte of data)
msg.data = bytearray([ord('E'), enable]) # 'E' for the command, followed by 0 or 1
try:
bus.send(msg)
state = "enabled" if enable else "disabled"
print(f"Sent message to {state} motor")
except can.CanError as e:
print(f"Message failed to send: {e}")
sys.exit(1) # Exit the program on failure
send_target_speed(bus,0.0)
def main():
# CAN interface setup
bus = None # Define outside the try block for proper shutdown
try:
bus = can.interface.Bus(channel='COM4', bustype='slcan', bitrate=1000000) # Ensure the bitrate matches the microcontroller settings
print("CAN bus initialized.")
while True:
user_input = input("Enter target speed: ")
if user_input.lower() == 'exit':
print("Exiting...")
break
try:
target_speed = float(user_input)
send_target_speed(bus, target_speed)
except ValueError:
print("Invalid input. Please enter a valid number.")
# Disable motor before exiting
send_motor_enable(bus, 0)
print("Motor disabled.")
except Exception as e:
print(f"Error initializing1 CAN bus: {e}")
sys.exit(1)
finally:
if bus is not None:
bus.shutdown()
print("CAN bus shut down.")
if __name__ == '__main__':
main()

View file

@ -0,0 +1,35 @@
import can
import struct
import time
# Function to send the target speed
def send_target_speed(bus, target_speed):
msg = can.Message()
msg.arbitration_id = 1 # Message ID
msg.is_extended_id = False
msg.dlc = 5 # Message length
msg.data = [ord('V')] + list(struct.pack('<f', target_speed)) # 'V' for the command identifier, followed by the speed in float format
try:
bus.send(msg)
print(f"Sent message with target speed: {target_speed} m/s")
print(f"Message data: {msg.data}")
except can.CanError:
print("Message failed to send")
# Main function
def main():
# CAN interface setup
bus = can.interface.Bus(channel='can0', bustype='socketcan', bitrate=1000000) # Ensure the bitrate matches the microcontroller settings
print("CAN bus initialized, sending target speed impulses...")
# Send impulses of target speed from -2 to 2 m/s
target_speeds = [-1, 1]
while True:
for speed in target_speeds:
send_target_speed(bus, speed)
time.sleep(1) # 1-second delay between messages
if __name__ == '__main__':
main()

View file

@ -0,0 +1,124 @@
import can
import time
import sys
# Конфигурация
CAN_INTERFACE = 'can0'
OLD_DEVICE_ID = int(sys.argv[1])
NEW_DEVICE_ID = int(sys.argv[2])
REG_WRITE = 0x8
REG_READ = 0x7
REG_ID = 0x1
def send_can_message(bus, can_id, data):
"""Отправка CAN-сообщения"""
try:
msg = can.Message(
arbitration_id=can_id,
data=data,
is_extended_id=False
)
bus.send(msg)
print(f"[Отправка] CAN ID: 0x{can_id:03X}, Данные: {list(data)}")
return True
except can.CanError as e:
print(f"Ошибка CAN: {e}")
return False
def receive_response(bus, timeout=1.0):
"""Ожидание ответа"""
start_time = time.time()
while time.time() - start_time < timeout:
msg = bus.recv(timeout=0.1)
if msg:
print(f"[Прием] CAN ID: 0x{msg.arbitration_id:03X}, Данные: {list(msg.data)}")
return msg
print("[Ошибка] Таймаут")
return None
def validate_crc16(data):
"""Функция расчета CRC16 (MODBUS)"""
crc = 0xFFFF
for byte in data:
crc ^= byte
for _ in range(8):
if crc & 0x0001:
crc = (crc >> 1) ^ 0xA001
else:
crc >>= 1
return crc
# Инициализация
bus = can.interface.Bus(channel=CAN_INTERFACE, bustype='socketcan')
# ======= 1. Отправляем команду изменить ID =======
# Весь буфер: id + команда + параметры
OLD_WITH_REG = (OLD_DEVICE_ID << 4) | REG_WRITE
id_bytes = list(OLD_WITH_REG.to_bytes(2, byteorder='little'))
# Важные части сообщения: address (id), команда, параметры
data_write = [REG_ID, NEW_DEVICE_ID] # команда изменить ID
# Полностью собираем массив для CRC (включая id и команду)
full_data_for_crc = id_bytes + data_write
# Расчет CRC по всему пакету
crc = validate_crc16(full_data_for_crc)
crc_bytes = list(crc.to_bytes(2, byteorder='little'))
# Итоговый пакет: команда + параметры + CRC
packet_write = data_write + crc_bytes
print("Отправляем: команда изменить ID + CRC:", packet_write)
# Отправляем с `OLD_DEVICE_ID` в качестве адреса
send_can_message(bus, (OLD_DEVICE_ID << 4) | REG_WRITE, packet_write)
time.sleep(1.0)
# ======= 2. Запрашиваем текущий ID (используем новый адрес) =======
# Теперь для запроса используем **уже новый id**
NEW_WITH_REG = (NEW_DEVICE_ID << 4) | REG_READ
current_id_bytes = list(NEW_WITH_REG.to_bytes(2, byteorder='little'))
data_read = [REG_ID, 0x00]
full_data_for_crc = current_id_bytes + data_read
crc = validate_crc16(full_data_for_crc)
crc_bytes = list(crc.to_bytes(2, byteorder='little'))
packet_read = data_read + crc_bytes
print("Запрос на чтение ID + CRC (после смены):", packet_read)
send_can_message(bus, (NEW_DEVICE_ID << 4) | REG_READ, packet_read)
# ======= 3. Получение и проверка ответа =======
response = receive_response(bus)
if response:
data = response.data
if len(data) < 4:
print("Ответ слишком короткий")
else:
id_bytes = response.arbitration_id.to_bytes(1,byteorder='little')
#buff with id and data without CRC
full_data = list(id_bytes) + list(data[:-2])
print(f"Received full_data: {list(full_data)}")
received_crc = int.from_bytes(data[-2:], byteorder='little')
#calc CRC
calc_crc = validate_crc16(full_data)
if received_crc == calc_crc:
if data[0] == ord('I') and data[1] == NEW_DEVICE_ID:
print(f"\nУСПЕХ! ID устройства изменен на 0x{NEW_DEVICE_ID:02X}")
else:
print(f"Некорректный ответ: {list(data)}")
else:
print("CRC не совпадает, данные повреждены.")
else:
print("Нет ответа от устройства.")
bus.shutdown()
if __name__ == "__main__":
import sys
if len(sys.argv) != 3:
print("Использование: python3 can_flasher.py old_addr new addr")
sys.exit(1)

View file

@ -0,0 +1,78 @@
import subprocess
import os
import sys
def flash_hex_with_stlink(hex_file_path):
if not os.path.isfile(hex_file_path):
print(f"❌ Файл не найден: {hex_file_path}")
return False
command = [
"st-flash",
"--format", "ihex",
"write",
hex_file_path
]
try:
print(f"⚡️ Прошиваем {hex_file_path} через ST-Link...")
result = subprocess.run(
command,
stdout=subprocess.PIPE,
stderr=subprocess.PIPE,
universal_newlines=True,
timeout=30
)
print("▬▬▬ STDOUT ▬▬▬")
print(result.stdout)
print("▬▬▬ STDERR ▬▬▬")
print(result.stderr)
if result.returncode == 0:
print("✅ Прошивка успешно завершена!")
# Добавленный блок сброса
try:
print("🔄 Выполняем сброс устройства...")
reset_result = subprocess.run(
["st-info", "--reset"],
stdout=subprocess.PIPE,
stderr=subprocess.PIPE,
universal_newlines=True,
timeout=10
)
if reset_result.returncode == 0:
print("♻️ Устройство успешно сброшено!")
else:
print(f"⚠️ Ошибка (код: {reset_result.returncode})")
print("▬▬▬ STDERR сброса ▬▬▬")
print(reset_result.stderr)
except Exception as e:
print(f"⚠️ Ошибка при сбросе: {str(e)}")
return True
else:
print(f"❌ Ошибка прошивки (код: {result.returncode})")
return False
except FileNotFoundError:
print("❌ st-flash не найден! Установите stlink-tools.")
return False
except subprocess.TimeoutExpired:
print("❌ Таймаут операции! Проверьте подключение ST-Link.")
return False
except Exception as e:
print(f"❌ Неизвестная ошибка: {str(e)}")
return False
if __name__ == "__main__":
if len(sys.argv) != 2:
print("Использование: python stlink_flash.py <firmware.hex>")
sys.exit(1)
if flash_hex_with_stlink(sys.argv[1]):
sys.exit(0)
else:
sys.exit(1)

View file

@ -0,0 +1,100 @@
import subprocess
import os
import sys
import time
def flash_hex_with_stlink(hex_file_path, component_name):
if not os.path.isfile(hex_file_path):
print(f"❌ Файл {component_name} не найден: {hex_file_path}")
return False
command = [
"st-flash",
"--format", "ihex",
"write",
hex_file_path
]
try:
print(f"⚡️ Прошиваем {component_name} ({hex_file_path}) через ST-Link...")
result = subprocess.run(
command,
stdout=subprocess.PIPE,
stderr=subprocess.PIPE,
universal_newlines=True,
timeout=30
)
print("▬▬▬ STDOUT ▬▬▬")
print(result.stdout)
print("▬▬▬ STDERR ▬▬▬")
print(result.stderr)
if result.returncode == 0:
print(f"{component_name} успешно прошит!")
return True
else:
print(f"❌ Ошибка прошивки {component_name} (код: {result.returncode})")
return False
except FileNotFoundError:
print("❌ st-flash не найден! Установите stlink-tools.")
return False
except subprocess.TimeoutExpired:
print(f"❌ Таймаут операции при прошивке {component_name}! Проверьте подключение ST-Link.")
return False
except Exception as e:
print(f"❌ Неизвестная ошибка при прошивке {component_name}: {str(e)}")
return False
def reset_device():
try:
print("🔄 Выполняем сброс(перезагрузку) устройства...")
reset_result = subprocess.run(
["st-info", "--reset"],
stdout=subprocess.PIPE,
stderr=subprocess.PIPE,
universal_newlines=True,
timeout=10
)
if reset_result.returncode == 0:
print("♻️ Устройство успешно сброшено!")
return True
else:
print(f"⚠️ Ошибка при сбросе (код: {reset_result.returncode})")
print("▬▬▬ STDERR сброса ▬▬▬")
print(reset_result.stderr)
return False
except Exception as e:
print(f"⚠️ Ошибка при сбросе: {str(e)}")
return False
if __name__ == "__main__":
if len(sys.argv) != 3:
print("Использование: python stlink_flash.py <bootloader.hex> <application.hex>")
print("Пример: python stlink_flash.py bootloader.hex firmware.hex")
sys.exit(1)
bootloader_path = sys.argv[1]
app_path = sys.argv[2]
# Прошиваем сначала бутлоадер
if not flash_hex_with_stlink(bootloader_path, "Bootloader"):
print("\n💥 Ошибка прошивки бутлоадера!")
sys.exit(1)
# Сбрасываем устройство после прошивки бутлоадера
reset_device()
time.sleep(1) # Короткая пауза
# Прошиваем основное приложение
if not flash_hex_with_stlink(app_path, "Application"):
print("\n💥 Ошибка прошивки основного приложения!")
sys.exit(1)
# Финальный сброс устройства
reset_device()
print("\n🎉 Все компоненты успешно прошиты!")
sys.exit(0)

View file

@ -0,0 +1,95 @@
import can
import time
import struct
import sys
# Конфигурация
CAN_INTERFACE = 'can0'
DEVICE_ID = int(sys.argv[1]) # ID ADDR for servo
REG_WRITE = 0x8 # Код команды записи
REG_MOTOR_POSPID_Kp = 0x30
REG_MOTOR_POSPID_Ki = 0x31
REG_MOTOR_POSPID_Kd = 0x32
def send_can_message(bus, can_id, data):
"""Отправка CAN-сообщения"""
try:
msg = can.Message(
arbitration_id=can_id,
data=data,
is_extended_id=False
)
bus.send(msg)
print(f"[Отправка] CAN ID: 0x{can_id:03X}, Данные: {list(data)}")
return True
except can.CanError as e:
print(f"Ошибка CAN: {e}")
return False
def validate_crc16(data):
"""Расчет CRC16 (MODBUS) для проверки целостности данных"""
crc = 0xFFFF
for byte in data:
crc ^= byte
for _ in range(8):
if crc & 0x0001:
crc = (crc >> 1) ^ 0xA001
else:
crc >>= 1
return crc
def send_pid_value(bus, device_id, reg, value):
"""Отправка коэффициента PID на устройство"""
# Формируем CAN ID для записи: (device_id << 4) | REG_WRITE
can_id_write = (device_id << 4) | REG_WRITE
# Упаковываем значение в байты (little-endian)
float_bytes = struct.pack('<f', value)
# Формируем часть данных (регистр + значение)
data_part = [reg] + list(float_bytes)
# Полные данные для расчета CRC: CAN ID + данные
full_data_for_crc = list(can_id_write.to_bytes(2, 'little')) + data_part
# Рассчитываем CRC и разбиваем на байты (little-endian)
crc = validate_crc16(full_data_for_crc)
crc_bytes = list(crc.to_bytes(2, 'little'))
# Собираем итоговый пакет данных
can_data = data_part + crc_bytes
# Отправляем сообщение
send_can_message(bus, can_id_write, can_data)
def main():
# Запрос коэффициентов у пользователя
try:
p = float(input("Введите коэффициент P: "))
i = float(input("Введите коэффициент I: "))
d = float(input("Введите коэффициент D: "))
except ValueError:
print("Ошибка: Введите числовые значения.")
return
# Инициализация CAN-интерфейса
bus = can.interface.Bus(channel=CAN_INTERFACE, bustype='socketcan')
try:
# Отправка коэффициентов с задержкой
send_pid_value(bus, DEVICE_ID, REG_MOTOR_POSPID_Kp, p)
time.sleep(1)
send_pid_value(bus, DEVICE_ID, REG_MOTOR_POSPID_Ki, i)
time.sleep(1)
send_pid_value(bus, DEVICE_ID, REG_MOTOR_POSPID_Kd, d)
finally:
# Завершение работы с шиной
bus.shutdown()
if __name__ == "__main__":
if len(sys.argv) != 2:
print("Используйте python3 pid_set.py addr")
sys.exit(1)
main()

View file

@ -0,0 +1,122 @@
import can
import time
import struct
# Конфигурация
CAN_INTERFACE = 'can0'
DEVICE_ID = 0x00
SET_PID_P = 3.6
REG_WRITE = 0x8
REG_READ = 0x7
REG_ID = 0x30 #REG_MOTOR_POSPID_Kp
PID_P = 0x01
def send_can_message(bus, can_id, data):
"""Отправка CAN-сообщения"""
try:
msg = can.Message(
arbitration_id=can_id,
data=data,
is_extended_id=False
)
bus.send(msg)
print(f"[Отправка] CAN ID: 0x{can_id:03X}, Данные: {list(data)}")
return True
except can.CanError as e:
print(f"Ошибка CAN: {e}")
return False
def receive_response(bus, timeout=1.0):
print("Ожидание ответа")
start_time = time.time()
while time.time() - start_time < timeout:
msg = bus.recv(timeout=0.1)
if msg:
print(f"[Прием] CAN ID: 0x{msg.arbitration_id:03X}, Данные: {list(msg.data)}")
return msg
print("[Ошибка] Таймаут")
return None
def validate_crc16(data):
"""Функция расчета CRC16 (MODBUS)"""
crc = 0xFFFF
for byte in data:
crc ^= byte
for _ in range(8):
if crc & 0x0001:
crc = (crc >> 1) ^ 0xA001
else:
crc >>= 1
return crc
# Инициализация
bus = can.interface.Bus(channel=CAN_INTERFACE, bustype='socketcan')
# Перевод float -> hex -> int
result = (struct.unpack('<I',struct.pack('<f', float(SET_PID_P)))[0])
result_bytes = result.to_bytes(4, byteorder='little')
# ======= 1. Отправляем команду изменить ID =======
# Весь буфер: id + команда + параметры
OLD_WITH_REG = (DEVICE_ID << 4) | REG_WRITE
id_bytes = list(OLD_WITH_REG.to_bytes(2, byteorder='little'))
# Важные части сообщения: address (id), команда, параметры
data_write = [REG_ID] + list(result_bytes) # команда изменить PID_P
# Полностью собираем массив для CRC (включая id и команду)
full_data_for_crc = id_bytes + data_write
# Расчет CRC по всему пакету
crc = validate_crc16(full_data_for_crc)
crc_bytes = list(crc.to_bytes(2, byteorder='little'))
# Итоговый пакет: команда + параметры + CRC
packet_write = data_write + crc_bytes
print("Отправляем: команда изменить PID_p + CRC:", packet_write)
# Отправляем с `OLD_DEVICE_ID` в качестве адреса
send_can_message(bus, (DEVICE_ID << 4) | REG_WRITE, packet_write)
time.sleep(1.0)
# ======= 2. Запрашиваем текущий ID (используем новый адрес) =======
# Теперь для запроса используем **уже новый id**
NEW_WITH_REG = (DEVICE_ID << 4) | REG_READ
current_id_bytes = list(NEW_WITH_REG.to_bytes(2, byteorder='little'))
data_read = [REG_ID, 0x00]
full_data_for_crc = current_id_bytes + data_read
crc = validate_crc16(full_data_for_crc)
crc_bytes = list(crc.to_bytes(2, byteorder='little'))
packet_read = data_read + crc_bytes
print("Запрос на чтение ID + CRC (после смены):", packet_read)
send_can_message(bus, (DEVICE_ID << 4) | REG_READ, packet_read)
# ======= 3. Получение и проверка ответа =======
response = receive_response(bus)
if response:
data = response.data
if len(data) < 4:
print("Ответ слишком короткий")
else:
id_bytes = response.arbitration_id.to_bytes(1,byteorder='little')
#buff with id and data without CRC
full_data = list(id_bytes) + list(data[:-2])
print(f"Received full_data: {list(full_data)}")
received_crc = int.from_bytes(data[-2:], byteorder='little')
#calc CRC
calc_crc = validate_crc16(full_data)
if received_crc == calc_crc:
if data[0] == int(REG_ID):
kp_val = struct.unpack('<f', bytes(data[1:5]))[0]
print(f"\nУСПЕХ! PID_P = {kp_val:.3f}")
else:
print(f"Некорректный ответ: {list(data)}")
else:
print("CRC не совпадает, данные повреждены.")
else:
print("Нет ответа от устройства.")
bus.shutdown()

View file

@ -0,0 +1,4 @@
#!/bin/bash
ip link set can0 type can bitrate 1000000
ip link set up can0

View file

@ -0,0 +1,34 @@
#!/bin/bash
# Read 8 byte ascii from $1 and send it to CAN bus
# <can_id>:
# 3 (SFF) or 8 (EFF) hex chars
# {data}:
# 0..8 (0..64 CAN FD) ASCII hex-values (optionally separated by '.')
# {len}:
# an optional 0..8 value as RTR frames can contain a valid dlc field
# <flags>:
# a single ASCII Hex value (0 .. F) which defines canfd_frame.flags
can_id=$1
input=$2
if [[ ${#input} -gt 8 ]]; then
echo "Error: Input string must be no longer than 8 characters."
exit 1
fi
hex_output=""
for (( i=0; i<${#input}; i++ )); do
hex_char=$(printf "%02x" "'${input:$i:1}")
hex_output+="${hex_char}"
done
hex_output=$(printf "%-16s" "$hex_output")
hex_output=${hex_output// /0}
can_id=$(printf "%03X" $can_id)
cansend can0 $can_id#$hex_output

View file

@ -0,0 +1,30 @@
#!/bin/bash
/bin/bash $(pwd)/send_can.sh 1 E0
/bin/bash $(pwd)/send_can.sh 1 E1
/bin/bash $(pwd)/send_can.sh 1 C2
/bin/bash $(pwd)/send_can.sh 1 1
sleep 1
/bin/bash $(pwd)/send_can.sh 1 -1
sleep 1
/bin/bash $(pwd)/send_can.sh 1 -1
sleep 1
/bin/bash $(pwd)/send_can.sh 1 2
sleep 1
/bin/bash $(pwd)/send_can.sh 1 C1
sleep 1
/bin/bash $(pwd)/send_can.sh 1 0.5
sleep 5
/bin/bash $(pwd)/send_can.sh 1 2
sleep 5
/bin/bash $(pwd)/send_can.sh 1 5
sleep 5
/bin/bash $(pwd)/send_can.sh 1 -5
sleep 5
/bin/bash $(pwd)/send_can.sh 1 20
sleep 5
/bin/bash $(pwd)/send_can.sh 1 E0

View file

@ -67,7 +67,7 @@
39,
40
],
"visible_layers": "0003ef3_80000001",
"visible_layers": "0001010_00000001",
"zone_display_mode": 0
},
"git": {

View file

@ -74,6 +74,7 @@
"footprint_type_mismatch": "ignore",
"hole_clearance": "error",
"hole_near_hole": "error",
"holes_co_located": "warning",
"invalid_outline": "error",
"isolated_copper": "warning",
"item_on_disabled_layer": "error",
@ -830,7 +831,7 @@
"plot": "",
"pos_files": "",
"specctra_dsn": "",
"step": "",
"step": "../../../../motor_controller_50mm_new.step",
"svg": "",
"vrml": ""
},

View file

@ -1698,6 +1698,188 @@
)
)
)
(symbol "Device:L_45deg"
(pin_numbers hide)
(pin_names
(offset 0)
)
(exclude_from_sim no)
(in_bom yes)
(on_board yes)
(property "Reference" "L"
(at 5.08 2.54 0)
(effects
(font
(size 1.27 1.27)
)
)
)
(property "Value" "L_45deg"
(at 8.255 0.635 0)
(effects
(font
(size 1.27 1.27)
)
)
)
(property "Footprint" ""
(at 0 1.778 0)
(effects
(font
(size 1.27 1.27)
)
(hide yes)
)
)
(property "Datasheet" "~"
(at 0 0 0)
(effects
(font
(size 1.27 1.27)
)
(hide yes)
)
)
(property "Description" "Inductor, rotated by 45°"
(at 0 0 0)
(effects
(font
(size 1.27 1.27)
)
(hide yes)
)
)
(property "ki_keywords" "inductor choke coil reactor magnetic inductor"
(at 0 0 0)
(effects
(font
(size 1.27 1.27)
)
(hide yes)
)
)
(property "ki_fp_filters" "L_* Choke_* Inductor_* *Coil*"
(at 0 0 0)
(effects
(font
(size 1.27 1.27)
)
(hide yes)
)
)
(symbol "L_45deg_0_1"
(polyline
(pts
(xy -1.27 1.27) (xy -2.54 2.54)
)
(stroke
(width 0)
(type default)
)
(fill
(type none)
)
)
(polyline
(pts
(xy 2.54 -2.54) (xy 1.27 -1.27)
)
(stroke
(width 0)
(type default)
)
(fill
(type none)
)
)
)
(symbol "L_45deg_1_1"
(arc
(start -0.635 0.635)
(mid -0.6462 1.2588)
(end -1.27 1.27)
(stroke
(width 0.254)
(type default)
)
(fill
(type none)
)
)
(arc
(start 0 0)
(mid -0.0062 0.6288)
(end -0.635 0.635)
(stroke
(width 0.254)
(type default)
)
(fill
(type none)
)
)
(arc
(start 0.635 -0.635)
(mid 0.6256 -0.0094)
(end 0 0)
(stroke
(width 0.254)
(type default)
)
(fill
(type none)
)
)
(arc
(start 1.27 -1.27)
(mid 1.265 -0.6449)
(end 0.635 -0.635)
(stroke
(width 0.254)
(type default)
)
(fill
(type none)
)
)
(pin passive line
(at 2.54 -2.54 180)
(length 0)
(name "~"
(effects
(font
(size 1.27 1.27)
)
)
)
(number "1"
(effects
(font
(size 1.27 1.27)
)
)
)
)
(pin passive line
(at -2.54 2.54 0)
(length 0)
(name "~"
(effects
(font
(size 1.27 1.27)
)
)
)
(number "2"
(effects
(font
(size 1.27 1.27)
)
)
)
)
)
)
(symbol "Device:R"
(pin_numbers hide)
(pin_names
@ -5801,6 +5983,12 @@
(color 0 0 0 0)
(uuid "38c69b4b-311f-4415-bc2b-099aa87991af")
)
(junction
(at 494.03 129.54)
(diameter 0)
(color 0 0 0 0)
(uuid "3c3925ae-53c6-4627-a632-7235c4c3d314")
)
(junction
(at 444.5 59.69)
(diameter 0)
@ -5957,6 +6145,12 @@
(color 0 0 0 0)
(uuid "8e9280c1-6aad-409b-ab8c-fc916265b5a7")
)
(junction
(at 491.49 170.18)
(diameter 0)
(color 0 0 0 0)
(uuid "912cec1e-3504-4dab-af40-a2051d7e2b14")
)
(junction
(at 452.12 82.55)
(diameter 0)
@ -6095,6 +6289,12 @@
(color 0 0 0 0)
(uuid "daced859-6ad5-4317-9265-02c3cecd416a")
)
(junction
(at 538.48 156.21)
(diameter 0)
(color 0 0 0 0)
(uuid "de67082a-0c22-40de-aba0-22d35d21b2a0")
)
(junction
(at 251.46 217.17)
(diameter 0)
@ -6119,6 +6319,12 @@
(color 0 0 0 0)
(uuid "e44a3bdd-f73e-4b73-870d-ae5fe4c397d3")
)
(junction
(at 492.76 204.47)
(diameter 0)
(color 0 0 0 0)
(uuid "e49f204d-811f-47b8-9089-30926b942c82")
)
(junction
(at 452.12 252.73)
(diameter 0)
@ -6623,6 +6829,16 @@
)
(uuid "12c8b6b8-0ec1-418a-96fd-ecc53ba0f0e2")
)
(wire
(pts
(xy 529.59 129.54) (xy 494.03 129.54)
)
(stroke
(width 0)
(type default)
)
(uuid "131897dc-1113-4984-a5ce-952d8bbc32c0")
)
(wire
(pts
(xy 302.26 209.55) (xy 293.37 209.55)
@ -6783,16 +6999,6 @@
)
(uuid "19f5f9d0-f4c4-4fb3-831f-a835e286c514")
)
(wire
(pts
(xy 477.52 170.18) (xy 477.52 166.37)
)
(stroke
(width 0)
(type default)
)
(uuid "1a0eb7da-427d-44c5-beec-e15045cbfcf4")
)
(wire
(pts
(xy 257.81 217.17) (xy 251.46 217.17)
@ -7153,6 +7359,16 @@
)
(uuid "331eed92-469f-4f1a-9fb1-c511733f970f")
)
(wire
(pts
(xy 492.76 204.47) (xy 557.53 204.47)
)
(stroke
(width 0)
(type default)
)
(uuid "3331a88b-8771-4acb-93d8-d5b5d12b509c")
)
(wire
(pts
(xy 91.44 227.33) (xy 102.87 227.33)
@ -7333,16 +7549,6 @@
)
(uuid "42ff8e11-5385-4e53-833a-ed6690e3c7b4")
)
(wire
(pts
(xy 538.48 166.37) (xy 477.52 166.37)
)
(stroke
(width 0)
(type default)
)
(uuid "43939165-d654-477e-abf6-b227efb47edc")
)
(wire
(pts
(xy 72.39 85.09) (xy 72.39 86.36)
@ -7473,6 +7679,16 @@
)
(uuid "489f12ba-0516-485d-b390-2b8057334cee")
)
(wire
(pts
(xy 491.49 170.18) (xy 491.49 165.1)
)
(stroke
(width 0)
(type default)
)
(uuid "48e4f759-7e02-4489-a52b-61062183fd2a")
)
(wire
(pts
(xy 74.93 226.06) (xy 74.93 227.33)
@ -7565,7 +7781,7 @@
)
(wire
(pts
(xy 541.02 129.54) (xy 473.71 129.54)
(xy 494.03 129.54) (xy 473.71 129.54)
)
(stroke
(width 0)
@ -7613,6 +7829,16 @@
)
(uuid "517f8daf-c5f6-4af9-9e9a-09f74e435e2f")
)
(wire
(pts
(xy 494.03 125.73) (xy 494.03 129.54)
)
(stroke
(width 0)
(type default)
)
(uuid "52c23abf-b547-4af9-8321-5664a1f210aa")
)
(wire
(pts
(xy 232.41 276.86) (xy 246.38 276.86)
@ -7865,7 +8091,7 @@
)
(wire
(pts
(xy 473.71 204.47) (xy 539.75 204.47)
(xy 473.71 204.47) (xy 492.76 204.47)
)
(stroke
(width 0)
@ -7893,6 +8119,16 @@
)
(uuid "628bee6b-7a77-4cb3-bfaf-07aed46650ae")
)
(wire
(pts
(xy 529.59 156.21) (xy 529.59 129.54)
)
(stroke
(width 0)
(type default)
)
(uuid "630dcdcc-49da-4c8d-9571-f34acc6bae57")
)
(bus
(pts
(xy 220.98 204.47) (xy 220.98 209.55)
@ -7903,6 +8139,16 @@
)
(uuid "6345ef14-1a4f-48d6-8976-01b4e285752a")
)
(wire
(pts
(xy 557.53 151.13) (xy 557.53 204.47)
)
(stroke
(width 0)
(type default)
)
(uuid "638d166b-cc36-46a1-af86-4c79d6f49283")
)
(wire
(pts
(xy 273.05 176.53) (xy 273.05 201.93)
@ -7945,7 +8191,7 @@
)
(wire
(pts
(xy 449.58 170.18) (xy 477.52 170.18)
(xy 449.58 170.18) (xy 491.49 170.18)
)
(stroke
(width 0)
@ -8943,6 +9189,16 @@
)
(uuid "aa4e3a64-ffd4-4e66-970a-18769d5adffc")
)
(wire
(pts
(xy 543.56 170.18) (xy 491.49 170.18)
)
(stroke
(width 0)
(type default)
)
(uuid "abeb8355-1328-406b-a38d-882ec82a98b3")
)
(wire
(pts
(xy 414.02 74.93) (xy 414.02 67.31)
@ -9143,6 +9399,16 @@
)
(uuid "b918ac10-e4f8-4a8f-85fb-36ff88c13d94")
)
(wire
(pts
(xy 537.21 156.21) (xy 538.48 156.21)
)
(stroke
(width 0)
(type default)
)
(uuid "ba205271-d477-42a1-abd3-37b456c8da80")
)
(wire
(pts
(xy 363.22 275.59) (xy 345.44 275.59)
@ -9483,6 +9749,16 @@
)
(uuid "cef48e73-7ce1-434a-98f7-61657d3eb2ae")
)
(wire
(pts
(xy 492.76 198.12) (xy 492.76 204.47)
)
(stroke
(width 0)
(type default)
)
(uuid "cf8014a1-1465-427b-8aba-35391164e6fc")
)
(wire
(pts
(xy 447.04 252.73) (xy 452.12 252.73)
@ -9643,6 +9919,16 @@
)
(uuid "d7a57e91-b375-4e4f-b835-986426db8ec8")
)
(wire
(pts
(xy 543.56 161.29) (xy 543.56 170.18)
)
(stroke
(width 0)
(type default)
)
(uuid "d85642a9-17d0-4b91-aabe-6c2fc083baf8")
)
(wire
(pts
(xy 293.37 186.69) (xy 293.37 187.96)
@ -9923,6 +10209,16 @@
)
(uuid "e755e3d6-0c8b-4ced-9c22-61f984a7cbf6")
)
(wire
(pts
(xy 557.53 151.13) (xy 543.56 151.13)
)
(stroke
(width 0)
(type default)
)
(uuid "e79dee28-b3b3-4a43-ac0a-bf6df4e09611")
)
(wire
(pts
(xy 144.78 250.19) (xy 144.78 254)
@ -10285,7 +10581,7 @@
(uuid "01986c87-ea3d-4d13-ab1b-41513d003f0b")
)
(label "W"
(at 534.67 204.47 0)
(at 487.68 204.47 0)
(fields_autoplaced yes)
(effects
(font
@ -10362,7 +10658,7 @@
(uuid "11c42e64-6f65-485f-8bb6-aa79d85eec4c")
)
(label "V"
(at 534.67 166.37 0)
(at 487.68 170.18 0)
(fields_autoplaced yes)
(effects
(font
@ -10483,7 +10779,7 @@
(uuid "291e0bbb-a369-45ac-a2b4-c46768878b78")
)
(label "U"
(at 534.67 129.54 0)
(at 487.68 129.54 0)
(fields_autoplaced yes)
(effects
(font
@ -18333,7 +18629,7 @@
)
(symbol
(lib_id "Mechanical:MountingHole_Pad")
(at 541.02 127 0)
(at 494.03 123.19 0)
(unit 1)
(exclude_from_sim no)
(in_bom no)
@ -18341,7 +18637,7 @@
(dnp yes)
(uuid "00000000-0000-0000-0000-0000653d28e0")
(property "Reference" "U1"
(at 543.56 125.7554 0)
(at 496.57 121.9454 0)
(effects
(font
(size 1.27 1.27)
@ -18350,7 +18646,7 @@
)
)
(property "Value" "MountingHole_Pad"
(at 543.56 128.0668 0)
(at 496.57 124.2568 0)
(effects
(font
(size 1.27 1.27)
@ -18359,7 +18655,7 @@
)
)
(property "Footprint" "Connector_Pin:Pin_D1.0mm_L10.0mm_LooseFit"
(at 541.02 127 0)
(at 494.03 123.19 0)
(effects
(font
(size 1.27 1.27)
@ -18368,7 +18664,7 @@
)
)
(property "Datasheet" "~"
(at 541.02 127 0)
(at 494.03 123.19 0)
(effects
(font
(size 1.27 1.27)
@ -18377,7 +18673,7 @@
)
)
(property "Description" ""
(at 541.02 127 0)
(at 494.03 123.19 0)
(effects
(font
(size 1.27 1.27)
@ -18386,7 +18682,7 @@
)
)
(property "manf#" ""
(at 541.02 127 0)
(at 494.03 123.19 0)
(effects
(font
(size 1.27 1.27)
@ -18408,7 +18704,7 @@
)
(symbol
(lib_id "Mechanical:MountingHole_Pad")
(at 538.48 163.83 0)
(at 491.49 162.56 0)
(unit 1)
(exclude_from_sim no)
(in_bom no)
@ -18416,7 +18712,7 @@
(dnp yes)
(uuid "00000000-0000-0000-0000-0000653d3012")
(property "Reference" "V1"
(at 541.02 162.5854 0)
(at 494.03 161.3154 0)
(effects
(font
(size 1.27 1.27)
@ -18425,7 +18721,7 @@
)
)
(property "Value" "MountingHole_Pad"
(at 541.02 164.8968 0)
(at 494.03 163.6268 0)
(effects
(font
(size 1.27 1.27)
@ -18434,7 +18730,7 @@
)
)
(property "Footprint" "Connector_Pin:Pin_D1.0mm_L10.0mm_LooseFit"
(at 538.48 163.83 0)
(at 491.49 162.56 0)
(effects
(font
(size 1.27 1.27)
@ -18443,7 +18739,7 @@
)
)
(property "Datasheet" "~"
(at 538.48 163.83 0)
(at 491.49 162.56 0)
(effects
(font
(size 1.27 1.27)
@ -18452,7 +18748,7 @@
)
)
(property "Description" ""
(at 538.48 163.83 0)
(at 491.49 162.56 0)
(effects
(font
(size 1.27 1.27)
@ -18461,7 +18757,7 @@
)
)
(property "manf#" ""
(at 538.48 163.83 0)
(at 491.49 162.56 0)
(effects
(font
(size 1.27 1.27)
@ -18483,7 +18779,7 @@
)
(symbol
(lib_id "Mechanical:MountingHole_Pad")
(at 539.75 201.93 0)
(at 492.76 195.58 0)
(unit 1)
(exclude_from_sim no)
(in_bom no)
@ -18491,7 +18787,7 @@
(dnp yes)
(uuid "00000000-0000-0000-0000-0000653d37ec")
(property "Reference" "W1"
(at 542.29 200.6854 0)
(at 495.3 194.3354 0)
(effects
(font
(size 1.27 1.27)
@ -18500,7 +18796,7 @@
)
)
(property "Value" "MountingHole_Pad"
(at 542.29 202.9968 0)
(at 495.3 196.6468 0)
(effects
(font
(size 1.27 1.27)
@ -18509,7 +18805,7 @@
)
)
(property "Footprint" "Connector_Pin:Pin_D1.0mm_L10.0mm_LooseFit"
(at 539.75 201.93 0)
(at 492.76 195.58 0)
(effects
(font
(size 1.27 1.27)
@ -18518,7 +18814,7 @@
)
)
(property "Datasheet" "~"
(at 539.75 201.93 0)
(at 492.76 195.58 0)
(effects
(font
(size 1.27 1.27)
@ -18527,7 +18823,7 @@
)
)
(property "Description" ""
(at 539.75 201.93 0)
(at 492.76 195.58 0)
(effects
(font
(size 1.27 1.27)
@ -18536,7 +18832,7 @@
)
)
(property "manf#" ""
(at 539.75 201.93 0)
(at 492.76 195.58 0)
(effects
(font
(size 1.27 1.27)
@ -21762,6 +22058,142 @@
)
)
)
(symbol
(lib_id "Device:L_45deg")
(at 541.02 153.67 270)
(unit 1)
(exclude_from_sim no)
(in_bom no)
(on_board no)
(dnp no)
(uuid "414532b0-b634-4d81-abe5-90c945c529d7")
(property "Reference" "L3"
(at 537.972 152.146 90)
(effects
(font
(size 1.27 1.27)
)
(justify left)
)
)
(property "Value" "W phase"
(at 532.13 149.098 90)
(effects
(font
(size 1.27 1.27)
)
(justify left)
)
)
(property "Footprint" ""
(at 542.798 153.67 0)
(effects
(font
(size 1.27 1.27)
)
(hide yes)
)
)
(property "Datasheet" "~"
(at 541.02 153.67 0)
(effects
(font
(size 1.27 1.27)
)
(hide yes)
)
)
(property "Description" "Inductor, rotated by 45°"
(at 541.02 153.67 0)
(effects
(font
(size 1.27 1.27)
)
(hide yes)
)
)
(pin "2"
(uuid "4a632bdf-e756-46eb-941c-f58fd80e98e3")
)
(pin "1"
(uuid "17b77971-ccbe-481b-877c-946830eed99d")
)
(instances
(project "motor_controller_50mm"
(path "/59b011af-aa16-42e7-b91d-08a229fb46fa"
(reference "L3")
(unit 1)
)
)
)
)
(symbol
(lib_id "Device:L_45deg")
(at 541.02 158.75 0)
(unit 1)
(exclude_from_sim no)
(in_bom no)
(on_board no)
(dnp no)
(uuid "4eabbd4a-6c11-4ea7-8989-8483bd98ba8d")
(property "Reference" "L2"
(at 543.306 157.48 0)
(effects
(font
(size 1.27 1.27)
)
)
)
(property "Value" "V phase"
(at 548.132 160.02 0)
(effects
(font
(size 1.27 1.27)
)
)
)
(property "Footprint" ""
(at 541.02 156.972 0)
(effects
(font
(size 1.27 1.27)
)
(hide yes)
)
)
(property "Datasheet" "~"
(at 541.02 158.75 0)
(effects
(font
(size 1.27 1.27)
)
(hide yes)
)
)
(property "Description" "Inductor, rotated by 45°"
(at 541.02 158.75 0)
(effects
(font
(size 1.27 1.27)
)
(hide yes)
)
)
(pin "2"
(uuid "776dd402-6d5f-4f41-91cd-2bc6e7fc011f")
)
(pin "1"
(uuid "3c053b4f-708b-42a8-b44e-eb3af9e5b717")
)
(instances
(project "motor_controller_50mm"
(path "/59b011af-aa16-42e7-b91d-08a229fb46fa"
(reference "L2")
(unit 1)
)
)
)
)
(symbol
(lib_id "power:PWR_FLAG")
(at 459.74 260.35 0)
@ -21905,6 +22337,82 @@
)
)
)
(symbol
(lib_id "Device:L")
(at 533.4 156.21 270)
(unit 1)
(exclude_from_sim no)
(in_bom no)
(on_board no)
(dnp no)
(uuid "e7b14cdd-3622-4f1b-8924-d25672ba9c64")
(property "Reference" "L4"
(at 534.924 158.75 90)
(effects
(font
(size 1.27 1.27)
)
)
)
(property "Value" "U phase"
(at 532.13 161.29 90)
(effects
(font
(size 1.27 1.27)
)
)
)
(property "Footprint" ""
(at 533.4 156.21 0)
(effects
(font
(size 1.27 1.27)
)
(hide yes)
)
)
(property "Datasheet" "~"
(at 533.4 156.21 0)
(effects
(font
(size 1.27 1.27)
)
(hide yes)
)
)
(property "Description" "Inductor"
(at 533.4 156.21 0)
(effects
(font
(size 1.27 1.27)
)
(hide yes)
)
)
(property "manf#" ""
(at 533.4 156.21 0)
(effects
(font
(size 1.27 1.27)
)
(hide yes)
)
)
(pin "2"
(uuid "7391295e-60fe-480b-a2a3-fb8adfadf916")
)
(pin "1"
(uuid "cac3d900-3342-48bc-864c-71133a60c7e5")
)
(instances
(project "motor_controller_50mm"
(path "/59b011af-aa16-42e7-b91d-08a229fb46fa"
(reference "L4")
(unit 1)
)
)
)
)
(symbol
(lib_id "power:PWR_FLAG")
(at 251.46 217.17 0)

View file

@ -1,36 +0,0 @@
#include "AS5040.h"
AS5040Sensor::AS5040Sensor(uint16_t cs, uint16_t mosi, uint16_t miso, uint16_t sck) {
cs_ = cs;
mosi_ = mosi;
miso_ = miso;
sck_ = sck;
}
void AS5040Sensor::init(SPIClass *_spi) {
spi = _spi;
// 1MHz clock (AMS should be able to accept up to 10MHz)
settings = SPISettings(1000000, MSBFIRST, SPI_MODE0);
//setup pins
pinMode(cs_, OUTPUT);
pinMode(miso_, INPUT);
pinMode(mosi_, OUTPUT);
pinMode(sck_, OUTPUT);
spi->setMISO(miso_);
spi->setMOSI(mosi_);
spi->setSCLK(sck_);
spi->begin();
this->Sensor::init(); // call base class init
}
float AS5040Sensor::getSensorAngle() {
//SPI - begin transaction
spi->beginTransaction(settings);
//Send the command
digitalWrite(cs_, LOW);
uint16_t data = spi->transfer16(0x3FFF);
digitalWrite(cs_,HIGH);
//SPI - end transaction
spi->endTransaction();
data = (data) >> 5;
return (float)data * _2PI / cpr;
}

View file

@ -1,26 +0,0 @@
#pragma once
#include "SimpleFOC.h"
class AS5040Sensor : public Sensor {
public:
AS5040Sensor(uint16_t cs, uint16_t mosi, uint16_t miso, uint16_t sck);
/** sensor initialise pins */
void init(SPIClass *_spi = &SPI);
// implementation of abstract functions of the Sensor class
/** get current angle (rad) */
float getSensorAngle() override;
private:
uint16_t cs_ = 0;
uint16_t mosi_ = 0;
uint16_t miso_ = 0;
uint16_t sck_ = 0;
float cpr = 1024;
SPISettings settings;
SPIClass *spi;
};

View file

@ -1,122 +0,0 @@
#include <AS5040.h>
#include <Arduino.h>
#include <SPI.h>
#include <SimpleFOC.h>
#pragma region "Motor and sensor setup"
#define LED1 PC10
#define LED2 PC11
#define HARDWARE_SERIAL_RX_PIN PB7
#define HARDWARE_SERIAL_TX_PIN PB6
#define AS5040_CS PB15
#define AS5040_MISO PB14
#define AS5040_MOSI PC1
#define AS5040_SCLK PB10
#define CURRENT_SENSOR_1 PB1 // INA180A
#define CURRENT_SENSOR_2 PB0
#define CURRENT_SENSOR_3 PC5
#pragma endregion
// simple foc debug mode
#define DEBUG_SIMPLE_FOC
// Init AS5040
AS5040Sensor sensor(AS5040_CS, AS5040_MOSI, AS5040_MISO, AS5040_SCLK);
// Init iPower 6208
BLDCMotor motor = BLDCMotor(16);
// Init 3PWM driver DRV8313
BLDCDriver3PWM driver = BLDCDriver3PWM(PA8, PA9, PA10, PC6, PA11, PA12);
// Init current sense
InlineCurrentSense current_sense = InlineCurrentSense(
0.0263, 100, CURRENT_SENSOR_2, CURRENT_SENSOR_1, CURRENT_SENSOR_3);
// Init UART Commander
Commander command = Commander(Serial);
void doMotor(char *cmd) { command.motor(&motor, cmd); }
void setup() {
SimpleFOCDebug::enable(&Serial);
// Setup hardware serial
Serial.setRx(HARDWARE_SERIAL_RX_PIN);
Serial.setTx(HARDWARE_SERIAL_TX_PIN);
Serial.begin(115200);
// Init pins
pinMode(PC8, OUTPUT);
pinMode(PC9, OUTPUT);
pinMode(PA11, OUTPUT);
pinMode(PA12, OUTPUT);
pinMode(PA10, OUTPUT);
pinMode(PC6, OUTPUT);
pinMode(PA8, OUTPUT);
pinMode(PA9, OUTPUT);
pinMode(PA10, OUTPUT);
// end init pins
digitalWrite(PC8, HIGH);
digitalWrite(PC9, HIGH);
delay(1);
digitalWrite(PA11, HIGH);
digitalWrite(PA12, HIGH);
digitalWrite(PC6, HIGH);
sensor.init();
motor.linkSensor(&sensor);
driver.pwm_frequency = 20000;
driver.voltage_power_supply = 20;
driver.voltage_limit = 20;
driver.init();
motor.linkDriver(&driver);
current_sense.linkDriver(&driver);
motor.controller = MotionControlType::angle;
motor.torque_controller = TorqueControlType::foc_current;
motor.foc_modulation = FOCModulationType::SinePWM;
motor.voltage_limit = 20;
motor.velocity_limit = 20;
motor.useMonitoring(Serial);
motor.init();
current_sense.init();
motor.linkCurrentSense(&current_sense);
motor.torque_controller = TorqueControlType::foc_current;
motor.controller = MotionControlType::angle;
motor.motion_downsample = 0.0;
motor.PID_velocity.P = 0.5;
motor.PID_velocity.I = 10.0;
motor.PID_velocity.D = 0.0;
motor.PID_velocity.output_ramp = 1000.0;
motor.PID_velocity.limit = 2.0;
motor.LPF_velocity.Tf = 0.005;
motor.P_angle.P = 0.5;
motor.P_angle.I = 10;
motor.P_angle.D = 1;
motor.P_angle.output_ramp = 0.0;
motor.P_angle.limit = 20.0;
motor.LPF_angle.Tf = 0.0;
motor.PID_current_q.P = 3.0;
motor.PID_current_q.I = 300.0;
motor.PID_current_q.D = 0.0;
motor.PID_current_q.output_ramp = 0.0;
motor.PID_current_q.limit = 12.0;
motor.LPF_current_q.Tf = 0.005;
motor.PID_current_d.P = 3.0;
motor.PID_current_d.I = 300.0;
motor.PID_current_d.D = 0.0;
motor.PID_current_d.output_ramp = 0.0;
motor.PID_current_d.limit = 12.0;
motor.LPF_current_d.Tf = 0.005;
motor.velocity_limit = 20.0;
motor.voltage_limit = 20.0;
motor.current_limit = 2.0;
motor.sensor_offset = 0.0;
motor.phase_resistance = 3.608;
motor.foc_modulation = FOCModulationType::SinePWM;
motor.modulation_centered = 1.0;
command.add('M', doMotor, "motor");
motor.useMonitoring(Serial);
_delay(1000);
}
void loop() {
motor.loopFOC();
motor.move();
motor.monitor();
command.run();
}

View file

@ -1,11 +0,0 @@
This directory is intended for PlatformIO Test Runner and project tests.
Unit Testing is a software testing method by which individual units of
source code, sets of one or more MCU program modules together with associated
control data, usage procedures, and operating procedures, are tested to
determine whether they are fit for use. Unit testing finds problems early
in the development cycle.
More information about PlatformIO Unit Testing:
- https://docs.platformio.org/en/latest/advanced/unit-testing/index.html

Binary file not shown.

After

Width:  |  Height:  |  Size: 110 KiB

BIN
img/coil_winder_schema.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 82 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 70 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 60 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 56 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 67 KiB

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

19
motor/README.md Normal file
View file

@ -0,0 +1,19 @@
## Описание директорий и файлов
```[motor]
├── parts/ # Детали моторов
│ ├── 53mm/ # Детали для 53мм мотора с пластиковым ротором
│ ├── 53mm_metal/ # Детали для 53мм мотора с металлическим ротором
│ ├── 72mm/ # Детали для 72мм мотора с пластиковым ротором
│ ├── 72mm_metal/ # Детали для 72мм мотора с металлическим ротором
│ ├── magnetic_parts_dxf/ # Файлы для лазерной резки деталей металлических статоров
│ └── сommon_parts/ # Детали общие для разных моторов
├── _asm_53mm_metall_motor.SLDASM # Сборка мотора 53мм с металлическим ротором
├── _asm_53mm_motor.SLDASM # Сборка мотора 53мм с пластиковым ротором
├── _asm_72mm_metall_motor.SLDASM # Сборка мотора 72мм с металлическим ротором
└── _asm_72mm_motor.SLDASM # Сборка мотора 72мм с пластиковым ротором
```
Важно, что каждая сборка использует файлы из разных папок.
Поэтому, для открытия, необходимо скачать все папки.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

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