├── version
├── package_name
├── doc
├── commands
│ ├── alert_id.md
│ ├── string.md
│ ├── ALERTS_CONTROL.md
│ ├── LIGHTS_CONTROL.md
│ ├── REALTIME_DATA_IDS.md
│ ├── float16.md
│ ├── ALERTS_LIST.md
│ ├── index.md
│ ├── INFO.md
│ └── DATA_RECORD.md
├── index.md
└── realtime_value_tracking.md
├── vesc_pkg_lib
├── examples
│ ├── extension
│ │ ├── Makefile
│ │ └── code.c
│ ├── ssd1306
│ │ ├── Makefile
│ │ └── code.c
│ ├── thread
│ │ ├── Makefile
│ │ └── code.c
│ ├── speed_test
│ │ ├── Makefile
│ │ ├── code.c
│ │ └── README.md
│ ├── custom_data_comm
│ │ ├── Makefile
│ │ ├── buffer.h
│ │ ├── qml.qml
│ │ └── code.c
│ ├── ws2812
│ │ └── Makefile
│ └── config
│ │ ├── Makefile
│ │ ├── conf
│ │ ├── confxml.h
│ │ ├── confparser.h
│ │ ├── conf_general.h
│ │ ├── buffer.h
│ │ └── datatypes.h
│ │ ├── datatypes.h
│ │ └── code.c
├── stdperiph_stm32f4
│ ├── inc
│ │ ├── stm32f4xx_conf.h
│ │ ├── stm32f4xx_wwdg.h
│ │ ├── stm32f4_gpio_af.h
│ │ └── stm32f4xx_iwdg.h
│ └── CMSIS
│ │ ├── include
│ │ └── arm_const_structs.h
│ │ └── ST
│ │ └── system_stm32f4xx.h
├── README.md
├── conv.py
├── link.ld
├── utils
│ └── rb.h
├── rules.mk
└── st_types.h
├── src
├── .gitignore
├── booster.h
├── biquad.h
├── led_strip.c
├── konami.h
├── conf
│ ├── conf_general.h.in
│ └── buffer.h
├── imu.h
├── data_record.h
├── footpad_sensor.h
├── remote.h
├── pid.h
├── torque_tilt.h
├── charging.h
├── atr.h
├── led_strip.h
├── brake_tilt.h
├── turn_tilt.h
├── balance_filter.h
├── bms.h
├── data_recorder.h
├── time.c
├── haptic_feedback.h
├── biquad.c
├── Makefile
├── motor_control.h
├── konami.c
├── led_driver.h
├── charging.c
├── time.h
├── alert_tracker.h
├── footpad_sensor.c
├── lib
│ ├── circular_buffer.h
│ └── circular_buffer.c
├── state.h
├── imu.c
├── motor_data.h
├── leds.h
├── booster.c
├── utils.c
├── lcm.h
├── bms.c
├── pid.c
├── torque_tilt.c
├── brake_tilt.c
├── alert_tracker.c
├── remote.c
├── state.c
├── data.h
└── turn_tilt.c
├── .gitignore
├── .clangd
├── .pre-commit-config.yaml
├── pkgdesc.qml
├── lisp
├── package.lisp
└── bms.lisp
├── .github
├── actions
│ └── build
│ │ └── action.yml
└── workflows
│ ├── ci.yml
│ └── create_release.yml
├── .clang-format
├── README.md
├── Makefile
├── changelog.py
├── package_README.md
└── CONTRIBUTING.md
/version:
--------------------------------------------------------------------------------
1 | 1.2.0
2 |
--------------------------------------------------------------------------------
/package_name:
--------------------------------------------------------------------------------
1 | Refloat
2 |
--------------------------------------------------------------------------------
/doc/commands/alert_id.md:
--------------------------------------------------------------------------------
1 | # `alert_id`
2 |
3 | - `1: ALERT_FW_FAULT`
4 |
5 |
--------------------------------------------------------------------------------
/doc/index.md:
--------------------------------------------------------------------------------
1 | # Refloat Development Documentation
2 |
3 | - [Realtime Value Tracking](realtime_value_tracking.md)
4 | - [Commands Reference](commands/index.md)
5 |
--------------------------------------------------------------------------------
/vesc_pkg_lib/examples/extension/Makefile:
--------------------------------------------------------------------------------
1 | TARGET = example
2 |
3 | SOURCES = code.c
4 |
5 | VESC_C_LIB_PATH=../../
6 | include $(VESC_C_LIB_PATH)rules.mk
7 |
8 |
--------------------------------------------------------------------------------
/vesc_pkg_lib/examples/ssd1306/Makefile:
--------------------------------------------------------------------------------
1 | TARGET = ssdacc
2 |
3 | SOURCES = code.c
4 |
5 | VESC_C_LIB_PATH=../../
6 | include $(VESC_C_LIB_PATH)/rules.mk
7 |
8 |
--------------------------------------------------------------------------------
/vesc_pkg_lib/examples/thread/Makefile:
--------------------------------------------------------------------------------
1 | TARGET = example
2 |
3 | SOURCES = code.c
4 |
5 | VESC_C_LIB_PATH=../../
6 | include $(VESC_C_LIB_PATH)rules.mk
7 |
8 |
--------------------------------------------------------------------------------
/src/.gitignore:
--------------------------------------------------------------------------------
1 | conf/conf_default.h
2 | conf/conf_general.h
3 | conf/confparser.c
4 | conf/confparser.h
5 | conf/confxml.c
6 | conf/confxml.h
7 | package_lib.lisp
8 |
--------------------------------------------------------------------------------
/vesc_pkg_lib/examples/speed_test/Makefile:
--------------------------------------------------------------------------------
1 | TARGET = example
2 |
3 | SOURCES = code.c
4 |
5 | VESC_C_LIB_PATH=../../
6 | include $(VESC_C_LIB_PATH)rules.mk
7 |
8 |
--------------------------------------------------------------------------------
/.gitignore:
--------------------------------------------------------------------------------
1 | compile_commands.json
2 | package_README-gen.md
3 | ui.qml
4 |
5 | *.bin
6 | *.d
7 | *.elf
8 | *.list
9 | *.o
10 | *.obj
11 | *.so
12 | *.vescpkg
13 |
--------------------------------------------------------------------------------
/vesc_pkg_lib/examples/custom_data_comm/Makefile:
--------------------------------------------------------------------------------
1 | TARGET = example
2 |
3 | SOURCES = code.c buffer.c
4 |
5 | VESC_C_LIB_PATH=../../
6 | include $(VESC_C_LIB_PATH)rules.mk
7 |
8 |
--------------------------------------------------------------------------------
/vesc_pkg_lib/examples/ws2812/Makefile:
--------------------------------------------------------------------------------
1 | TARGET = ws2812
2 |
3 | SOURCES = code.c
4 |
5 | USE_STLIB = yes
6 | VESC_C_LIB_PATH=../../
7 | include $(VESC_C_LIB_PATH)rules.mk
8 |
9 |
--------------------------------------------------------------------------------
/vesc_pkg_lib/examples/config/Makefile:
--------------------------------------------------------------------------------
1 | TARGET = config
2 |
3 | SOURCES = code.c conf/buffer.c conf/confparser.c conf/confxml.c
4 |
5 | VESC_C_LIB_PATH=../../
6 | include $(VESC_C_LIB_PATH)rules.mk
7 |
8 |
--------------------------------------------------------------------------------
/.clangd:
--------------------------------------------------------------------------------
1 | CompileFlags:
2 | Add:
3 | - "-D_XOPEN_SOURCE=1" # M_PI definition error
4 | - "-Wall"
5 | - "-Wextra"
6 | - "-Wno-double-promotion" # suppress, clangd doesn't support -fsingle-precision-constant
7 |
--------------------------------------------------------------------------------
/.pre-commit-config.yaml:
--------------------------------------------------------------------------------
1 | repos:
2 | - repo: local
3 | hooks:
4 | - id: clang-format
5 | name: clang-format
6 | entry: clang-format -i
7 | language: system
8 | types: [c]
9 | exclude: ^vesc_pkg_lib/
10 |
--------------------------------------------------------------------------------
/doc/commands/string.md:
--------------------------------------------------------------------------------
1 | # `string`
2 |
3 | | Offset | Size | Name | Description |
4 | |--------|------|----------|---------------|
5 | | 0 | 1 | `length` | Length of the string. |
6 | | 1 | ? | `string` | `length` number of characters of the string (not null-terminated). |
7 |
8 |
--------------------------------------------------------------------------------
/doc/commands/ALERTS_CONTROL.md:
--------------------------------------------------------------------------------
1 | # Command: ALERTS_CONTROL
2 |
3 | **ID**: 36
4 |
5 | **Status**: **unstable**
6 |
7 | The alerts control command.
8 |
9 | | Offset | Size | Name | Mandatory | Description |
10 | |--------|------|-----------|-----------|---------------|
11 | | 0 | 1 | `command` | Yes | `1`: Clear Fatal Error
|
12 |
--------------------------------------------------------------------------------
/vesc_pkg_lib/examples/config/conf/confxml.h:
--------------------------------------------------------------------------------
1 | // This file is autogenerated by VESC Tool
2 |
3 | #ifndef CONFXML_H_
4 | #define CONFXML_H_
5 |
6 | #include "datatypes.h"
7 | #include
8 | #include
9 |
10 | // Constants
11 | #define DATA_BALANCE_CONFIG__SIZE 6723
12 |
13 | // Variables
14 | extern uint8_t data_balance_config_[];
15 |
16 | // CONFXML_H_
17 | #endif
18 |
--------------------------------------------------------------------------------
/vesc_pkg_lib/stdperiph_stm32f4/inc/stm32f4xx_conf.h:
--------------------------------------------------------------------------------
1 | #ifndef __STM32F4xx_CONF_H
2 | #define __STM32F4xx_CONF_H
3 |
4 | #define USE_RTOS 0
5 |
6 | #include "misc.h"
7 | #include "stm32f4_gpio_af.h"
8 | #include "stm32f4xx_dma.h"
9 | #include "stm32f4xx_adc.h"
10 | #include "stm32f4xx_exti.h"
11 | #include "stm32f4xx_flash.h"
12 | #include "stm32f4xx_rcc.h"
13 | #include "stm32f4xx_syscfg.h"
14 | #include "stm32f4xx_tim.h"
15 | #include "stm32f4xx_wwdg.h"
16 | #include "stm32f4xx_iwdg.h"
17 |
18 | #endif
19 |
--------------------------------------------------------------------------------
/pkgdesc.qml:
--------------------------------------------------------------------------------
1 | import QtQuick 2.15
2 |
3 | Item {
4 | property string pkgName: "Refloat"
5 | property string pkgDescriptionMd: "package_README-gen.md"
6 | property string pkgLisp: "lisp/package.lisp"
7 | property string pkgQml: "ui.qml"
8 | property bool pkgQmlIsFullscreen: false
9 | property string pkgOutput: "refloat.vescpkg"
10 |
11 | function isCompatible (fwRxParams) {
12 | if (fwRxParams.hwTypeStr().toLowerCase() != "vesc") {
13 | return false;
14 | }
15 |
16 | return true;
17 | }
18 | }
19 |
--------------------------------------------------------------------------------
/vesc_pkg_lib/README.md:
--------------------------------------------------------------------------------
1 | # VESC Package Library
2 |
3 | This is a VESC Package library containing the necessary files to build a VESC Package. It is intended to be included in a VESC Package repository as a `git subtree` in the `vesc_pkg_lib` directory.
4 |
5 | ## Adding the library to a repository
6 |
7 | ```bash
8 | git subtree add --prefix vesc_pkg_lib https://github.com/lukash/vesc_pkg_lib.git main --squash
9 | ```
10 |
11 | ## Updating the library in a repository to a new version
12 |
13 | ```bash
14 | git subtree pull --prefix vesc_pkg_lib https://github.com/lukash/vesc_pkg_lib.git main --squash
15 | ```
16 |
--------------------------------------------------------------------------------
/vesc_pkg_lib/examples/config/conf/confparser.h:
--------------------------------------------------------------------------------
1 | // This file is autogenerated by VESC Tool
2 |
3 | #ifndef CONFPARSER_H_
4 | #define CONFPARSER_H_
5 |
6 | #include "datatypes.h"
7 | #include
8 | #include
9 |
10 | // Constants
11 | #define BALANCE_CONFIG_SIGNATURE 32903057
12 |
13 | // Functions
14 | int32_t confparser_serialize_balance_config(uint8_t *buffer, const balance_config *conf);
15 | bool confparser_deserialize_balance_config(const uint8_t *buffer, balance_config *conf);
16 | void confparser_set_defaults_balance_config(balance_config *conf);
17 |
18 | // CONFPARSER_H_
19 | #endif
20 |
--------------------------------------------------------------------------------
/lisp/package.lisp:
--------------------------------------------------------------------------------
1 | (import "src/package_lib.bin" 'package-lib)
2 | (load-native-lib package-lib)
3 |
4 | (define fw-ver (sysinfo 'fw-ver))
5 | (apply ext-set-fw-version fw-ver)
6 |
7 | ; Start the BMS polling loop in a thread if enabled
8 | (if (ext-bms)
9 | (if (or (>= (first fw-ver) 7) (and (= (first fw-ver) 6) (>= (second fw-ver) 5)))
10 | (progn
11 | (import "bms.lisp" 'bms)
12 | (read-eval-program bms)
13 | (spawn "Refloat BMS" 50 bms-loop)
14 | )
15 | (print "[refloat] BMS Integration: Unsupported firmware version, 6.05+ required.")
16 | )
17 | )
18 |
--------------------------------------------------------------------------------
/.github/actions/build/action.yml:
--------------------------------------------------------------------------------
1 | name: Build Package
2 |
3 | inputs:
4 | cache-auth-token:
5 | description: Cachix auth token
6 | default: ""
7 |
8 | runs:
9 | using: "composite"
10 | steps:
11 | - uses: cachix/install-nix-action@v25
12 | - uses: cachix/cachix-action@v14
13 | with:
14 | name: refloat
15 | authToken: '${{ inputs.cache-auth-token }}'
16 | - uses: rrbutani/use-nix-shell-action@v1
17 | with:
18 | flakes: nixpkgs/nixos-24.11#gcc-arm-embedded-7, nixpkgs#gnumake, github:lukash/vesc_tool-flake/release_6_06
19 |
20 | - name: Build
21 | shell: bash
22 | run: make -j
23 |
--------------------------------------------------------------------------------
/.clang-format:
--------------------------------------------------------------------------------
1 | Language: Cpp
2 | IndentWidth: 4
3 | ColumnLimit: 100
4 |
5 | AlignAfterOpenBracket: BlockIndent
6 | AlignOperands: DontAlign
7 | AlignTrailingComments: Never
8 | AllowAllParametersOfDeclarationOnNextLine: true
9 | AllowShortEnumsOnASingleLine: false
10 | AllowShortFunctionsOnASingleLine: false
11 | AlwaysBreakAfterReturnType: None
12 | AlwaysBreakBeforeMultilineStrings: true
13 | BinPackArguments: false
14 | BinPackParameters: false
15 | BraceWrapping:
16 | AfterControlStatement: MultiLine
17 | InsertBraces: true
18 | InsertNewlineAtEOF: true
19 | PenaltyReturnTypeOnItsOwnLine: 10000
20 | SpaceAfterCStyleCast: true
21 | SpacesBeforeTrailingComments: 2
22 |
--------------------------------------------------------------------------------
/vesc_pkg_lib/conv.py:
--------------------------------------------------------------------------------
1 | import sys,getopt,binascii
2 |
3 | filename = ""
4 | name = "test"
5 |
6 | opts,args = getopt.getopt(sys.argv[1:],'f:n:')
7 | for o,a in opts:
8 | if o == '-f':
9 | filename = a
10 | if o == '-n':
11 | name = a
12 |
13 | with open(filename, "rb") as f:
14 | hexdata = f.read().hex()
15 | tokens = [hexdata[i:i+2] for i in range(0, len(hexdata), 2)]
16 | res = "(def " + name + " [\n"
17 | cnt = 0
18 | for c in tokens:
19 | res += "0x" + c
20 | cnt = cnt + 1
21 | if cnt == 20:
22 | cnt = 0
23 | res += "\n"
24 | else:
25 | res += " "
26 |
27 | if res[-1] == '\n':
28 | res += "])\n"
29 | else:
30 | res += "\n])\n"
31 | print(res)
32 |
33 |
--------------------------------------------------------------------------------
/.github/workflows/ci.yml:
--------------------------------------------------------------------------------
1 | name: CI
2 | on:
3 | push:
4 | branches: ["*"]
5 | tags: ["*"]
6 | pull_request:
7 | branches: ["*"]
8 |
9 | jobs:
10 | ci:
11 | name: CI
12 | runs-on: ubuntu-24.04
13 | steps:
14 | - uses: actions/checkout@v4
15 | - uses: cachix/install-nix-action@v25
16 | - uses: rrbutani/use-nix-shell-action@v1
17 | with:
18 | flakes: nixpkgs#llvmPackages_18.clang-tools, nixpkgs#pre-commit
19 |
20 | - name: Run clang-format
21 | id: clang-format
22 | run: pre-commit run --all-files --show-diff-on-failure --color always
23 |
24 | - name: Build Package
25 | if: success() || (failure() && steps.clang-format.conclusion == 'failure')
26 | uses: ./.github/actions/build
27 | with:
28 | cache-auth-token: '${{ secrets.CACHIX_AUTH_TOKEN }}'
29 |
--------------------------------------------------------------------------------
/doc/commands/LIGHTS_CONTROL.md:
--------------------------------------------------------------------------------
1 | # Command: LIGHTS_CONTROL
2 |
3 | **ID**: 20
4 |
5 | Controls the lights and returns current lighting state values.
6 |
7 | ## Request
8 |
9 | | Offset | Size | Name | Mandatory | Description |
10 | |--------|------|-----------|-----------|---------------|
11 | | 0 | 4 | `mask` | No | Mask determining which values are being set in the command. Bits 0..7 correspond to the `flags` bits. Bits 8..31 are unused. |
12 | | 4 | 1 | `flags` | No | Values of lighting flags to set. |
13 |
14 | ## Response
15 |
16 | | Offset | Size | Name | Description |
17 | |--------|------|---------|---------------|
18 | | 0 | 1 | `flags` | Current values of lighting flags. |
19 |
20 | ## Common Structures
21 |
22 | #### flags
23 |
24 | | 7-2 | 1 | 0 |
25 | |-----|-----------------|-----------|
26 | | 0 | `headlights_on` | `leds_on` |
27 |
--------------------------------------------------------------------------------
/vesc_pkg_lib/link.ld:
--------------------------------------------------------------------------------
1 | MEMORY
2 | {
3 | MEM : org = 0, len = 96k
4 | }
5 |
6 | SECTIONS
7 | {
8 | . = 0;
9 | _text = .;
10 |
11 | .program_ptr : ALIGN(4)
12 | {
13 | . = ALIGN(4);
14 | *(.program_ptr)
15 | } > MEM
16 |
17 | .init_fun : ALIGN(4)
18 | {
19 | . = ALIGN(4);
20 | *(.init_fun)
21 | } > MEM
22 |
23 | .data : ALIGN(4)
24 | {
25 | . = ALIGN(4);
26 | *(.data)
27 | } > MEM
28 |
29 | .bss : ALIGN(4)
30 | {
31 | . = ALIGN(4);
32 | *(.bss)
33 | } > MEM
34 |
35 | .got : ALIGN(4)
36 | {
37 | . = ALIGN(4);
38 | *(.got*)
39 | . = ALIGN(4);
40 | } > MEM
41 |
42 | .text : ALIGN(16) SUBALIGN(16)
43 | {
44 | *(.text)
45 | *(.rodata)
46 | *(.rodata.*)
47 | } > MEM
48 | }
49 |
50 |
--------------------------------------------------------------------------------
/vesc_pkg_lib/examples/config/conf/conf_general.h:
--------------------------------------------------------------------------------
1 | /*
2 | Copyright 2022 Benjamin Vedder benjamin@vedder.se
3 |
4 | This file is part of the VESC firmware.
5 |
6 | The VESC firmware is free software: you can redistribute it and/or modify
7 | it under the terms of the GNU General Public License as published by
8 | the Free Software Foundation, either version 3 of the License, or
9 | (at your option) any later version.
10 |
11 | The VESC firmware is distributed in the hope that it will be useful,
12 | but WITHOUT ANY WARRANTY; without even the implied warranty of
13 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14 | GNU General Public License for more details.
15 |
16 | You should have received a copy of the GNU General Public License
17 | along with this program. If not, see .
18 | */
19 |
20 | #ifndef CONF_GENERAL_H_
21 | #define CONF_GENERAL_H_
22 |
23 | #include "conf_default.h"
24 |
25 | // CONF_GENERAL_H_
26 | #endif
27 |
--------------------------------------------------------------------------------
/src/booster.h:
--------------------------------------------------------------------------------
1 | // Copyright 2025 Lukas Hrazky
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #pragma once
19 |
20 | #include "conf/datatypes.h"
21 | #include "motor_data.h"
22 |
23 | typedef struct {
24 | float current;
25 | } Booster;
26 |
27 | void booster_init(Booster *b);
28 |
29 | void booster_reset(Booster *b);
30 |
31 | void booster_update(
32 | Booster *b, const MotorData *md, const RefloatConfig *config, float proportional
33 | );
34 |
--------------------------------------------------------------------------------
/src/biquad.h:
--------------------------------------------------------------------------------
1 | // Copyright 2022 Benjamin Vedder
2 | // Copyright 2024 Lukas Hrazky
3 | //
4 | // This file is part of the Refloat VESC package.
5 | //
6 | // Refloat VESC package is free software: you can redistribute it and/or modify
7 | // it under the terms of the GNU General Public License as published by the
8 | // Free Software Foundation, either version 3 of the License, or (at your
9 | // option) any later version.
10 | //
11 | // Refloat VESC package is distributed in the hope that it will be useful, but
12 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
13 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
14 | // more details.
15 | //
16 | // You should have received a copy of the GNU General Public License along with
17 | // this program. If not, see .
18 |
19 | #pragma once
20 |
21 | typedef struct {
22 | float a0, a1, a2, b1, b2;
23 | float z1, z2;
24 | } Biquad;
25 |
26 | typedef enum {
27 | BQ_LOWPASS,
28 | BQ_HIGHPASS
29 | } BiquadType;
30 |
31 | float biquad_process(Biquad *biquad, float in);
32 |
33 | void biquad_configure(Biquad *biquad, BiquadType type, float frequency);
34 |
35 | void biquad_reset(Biquad *biquad);
36 |
--------------------------------------------------------------------------------
/src/led_strip.c:
--------------------------------------------------------------------------------
1 | // Copyright 2025 Lukas Hrazky
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #include "led_strip.h"
19 |
20 | #include
21 |
22 | void led_strip_init(LedStrip *strip) {
23 | strip->data = NULL;
24 | strip->length = 0;
25 | strip->color_order = LED_COLOR_GRB;
26 | strip->reverse = false;
27 | }
28 |
29 | void led_strip_configure(LedStrip *strip, const CfgLedStrip *cfg) {
30 | strip->length = cfg->count;
31 | strip->color_order = cfg->color_order;
32 | strip->reverse = cfg->reverse;
33 | }
34 |
--------------------------------------------------------------------------------
/src/konami.h:
--------------------------------------------------------------------------------
1 | // Copyright 2024 Lukas Hrazky
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #pragma once
19 |
20 | #include "footpad_sensor.h"
21 | #include "leds.h"
22 | #include "time.h"
23 |
24 | typedef struct {
25 | time_t timer;
26 | uint8_t state;
27 | const FootpadSensorState *sequence;
28 | uint8_t sequence_size;
29 | } Konami;
30 |
31 | void konami_init(Konami *konami, const FootpadSensorState *sequence, uint8_t sequence_size);
32 |
33 | bool konami_check(Konami *konami, Leds *leds, const FootpadSensor *fs, const Time *time);
34 |
--------------------------------------------------------------------------------
/src/conf/conf_general.h.in:
--------------------------------------------------------------------------------
1 | // Copyright 2022 Benjamin Vedder
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #ifndef CONF_GENERAL_H_
19 | #define CONF_GENERAL_H_
20 |
21 | #define PACKAGE_NAME "{{PACKAGE_NAME}}"
22 | #define PACKAGE_VERSION "{{VERSION}}"
23 | #define MAJOR_VERSION {{MAJOR_VERSION}}
24 | #define MINOR_VERSION {{MINOR_VERSION}}
25 | #define PATCH_VERSION {{PATCH_VERSION}}
26 | #define VERSION_SUFFIX "{{VERSION_SUFFIX}}"
27 | #define GIT_HASH 0x{{GIT_HASH}}
28 |
29 | #include "conf_default.h"
30 |
31 | // CONF_GENERAL_H_
32 | #endif
33 |
--------------------------------------------------------------------------------
/src/imu.h:
--------------------------------------------------------------------------------
1 | // Copyright 2025 Lukas Hrazky
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #pragma once
19 |
20 | #include "balance_filter.h"
21 | #include "state.h"
22 |
23 | typedef struct {
24 | float pitch;
25 | float balance_pitch;
26 | float roll;
27 | float yaw;
28 | float pitch_rate;
29 |
30 | float flywheel_pitch_offset;
31 | float flywheel_roll_offset;
32 | } IMU;
33 |
34 | void imu_init(IMU *imu);
35 |
36 | void imu_update(IMU *imu, const BalanceFilterData *bf, const State *state);
37 |
38 | void imu_set_flywheel_offsets(IMU *imu);
39 |
--------------------------------------------------------------------------------
/src/data_record.h:
--------------------------------------------------------------------------------
1 | // Copyright 2024 Lukas Hrazky
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #pragma once
19 |
20 | #include "lib/circular_buffer.h"
21 | #include "rt_data.h"
22 | #include "time.h"
23 |
24 | #include
25 | #include
26 |
27 | typedef struct {
28 | time_t time;
29 | uint8_t flags;
30 | uint16_t values[ITEMS_COUNT_REC(RT_DATA_ALL_ITEMS)]; // values encoded as float16
31 | } Sample;
32 |
33 | typedef struct {
34 | bool enabled;
35 | bool recording;
36 | bool autostart;
37 | bool autostop;
38 | CircularBuffer buffer;
39 | } DataRecord;
40 |
--------------------------------------------------------------------------------
/vesc_pkg_lib/examples/extension/code.c:
--------------------------------------------------------------------------------
1 | /*
2 | Copyright 2022 Benjamin Vedder benjamin@vedder.se
3 |
4 | This file is part of the VESC firmware.
5 |
6 | The VESC firmware is free software: you can redistribute it and/or modify
7 | it under the terms of the GNU General Public License as published by
8 | the Free Software Foundation, either version 3 of the License, or
9 | (at your option) any later version.
10 |
11 | The VESC firmware is distributed in the hope that it will be useful,
12 | but WITHOUT ANY WARRANTY; without even the implied warranty of
13 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14 | GNU General Public License for more details.
15 |
16 | You should have received a copy of the GNU General Public License
17 | along with this program. If not, see .
18 | */
19 |
20 | #include "vesc_c_if.h"
21 |
22 | HEADER
23 |
24 | static lbm_value ext_test(lbm_value *args, lbm_uint argn) {
25 | if (argn != 1 || !VESC_IF->lbm_is_number(args[0])) {
26 | return VESC_IF->lbm_enc_sym_eerror;
27 | }
28 |
29 | return VESC_IF->lbm_enc_i(VESC_IF->lbm_dec_as_i32(args[0]) * 3);
30 | }
31 |
32 | INIT_FUN(lib_info *info) {
33 | INIT_START
34 |
35 | (void)info;
36 | VESC_IF->lbm_add_extension("ext-test", ext_test);
37 | return true;
38 | }
39 |
40 |
--------------------------------------------------------------------------------
/doc/commands/REALTIME_DATA_IDS.md:
--------------------------------------------------------------------------------
1 | # Command: REALTIME_DATA_IDS
2 |
3 | **ID**: 32
4 |
5 | Returns a list of string IDs of the items sent in the [REALTIME_DATA](REALTIME_DATA.md) command. The number of items in that command, as well as their meaning, is defined by the two sequences of IDs obtained from this command.
6 |
7 | ## Request
8 |
9 | No data.
10 |
11 | ## Response
12 |
13 | Contains two sequences of string IDs for data that are sent in the [REALTIME_DATA](REALTIME_DATA.md) command.
14 |
15 | The actual list of IDs that are sent is in [rt_data.h](/src/rt_data.h). See [Realtime Value Tracking](../realtime_value_tracking.md) for more details.
16 |
17 | | Offset | Size | Name | Description |
18 | |--------|------|----------------------------------|---------------|
19 | | 0 | 1 | `realtime_data_id_count` | Number of IDs of the `REALTIME_DATA` items which are always sent. |
20 | | 1 | ? | `realtime_data_ids` | A [string](string.md) sequence repeated `realtime_data_id_count` times. |
21 | | ? | 1 | `realtime_runtime_data_id_count` | Number of IDs of the `REALTIME_DATA` items which are sent only when the package is running. |
22 | | ? | ? | `realtime_runtime_data_ids` | A [string](string.md) sequence repeated `realtime_runtime_data_id_count` times. |
23 |
--------------------------------------------------------------------------------
/src/footpad_sensor.h:
--------------------------------------------------------------------------------
1 | // Copyright 2024 Lukas Hrazky
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #pragma once
19 |
20 | #include "conf/datatypes.h"
21 |
22 | typedef enum {
23 | FS_NONE = 0,
24 | FS_LEFT = 1,
25 | FS_RIGHT = 2,
26 | FS_BOTH = 3
27 | } FootpadSensorState;
28 |
29 | typedef struct {
30 | float adc1, adc2;
31 | FootpadSensorState state;
32 | } FootpadSensor;
33 |
34 | void footpad_sensor_init(FootpadSensor *fs);
35 |
36 | void footpad_sensor_update(FootpadSensor *fs, const RefloatConfig *config);
37 |
38 | int footpad_sensor_state_to_switch_compat(FootpadSensorState v);
39 |
--------------------------------------------------------------------------------
/src/remote.h:
--------------------------------------------------------------------------------
1 | // Copyright 2025 Lukas Hrazky
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #pragma once
19 |
20 | #include "conf/datatypes.h"
21 | #include "state.h"
22 |
23 | typedef struct {
24 | float step_size;
25 |
26 | float input;
27 | float ramped_step_size;
28 |
29 | float setpoint;
30 | } Remote;
31 |
32 | void remote_init(Remote *remote);
33 |
34 | void remote_reset(Remote *remote);
35 |
36 | void remote_configure(Remote *remote, const RefloatConfig *config);
37 |
38 | void remote_input(Remote *remote, const RefloatConfig *config);
39 |
40 | void remote_update(Remote *remote, const State *state, const RefloatConfig *config);
41 |
--------------------------------------------------------------------------------
/doc/realtime_value_tracking.md:
--------------------------------------------------------------------------------
1 | # Realtime Value Tracking
2 |
3 | The package provides an easy-to-use mechanism to track realtime values which are not provided by default. It's as easy as modifying the list of values in [rt_data.h](/src/rt_data.h) and recompiling the package. The values are automatically propagated to the package UI (and 3rd party client apps, if they support it) via the [REALTIME_DATA](commands/REALTIME_DATA.md) command.
4 |
5 | ## Data Recording
6 |
7 | The package allows to record a short period of realtime data into an internal memory buffer at the native loop frequency. This functionality requires a special firmware that reserves the buffer in memory and passes its address and size to the package. This firmware can be found here: https://github.com/lukash/bldc/tree/release_6_05-datarecord
8 |
9 | The firmware with this information is automatically detected and advertised via `capabilities` in the [INFO](commands/INFO.md) command. In the package UI, the controls automatically appear in such case.
10 |
11 | The values that are recorded are defined along with the realtime values in [rt_data.h](/src/rt_data.h) and can be easily added or removed. The length of the recorded period depends on the amount of values. More values, shorter period fits into the buffer.
12 |
13 | On the command interface, the recording can be controlled via the [DATA_RECORD](commands/DATA_RECORD.md) command.
14 |
--------------------------------------------------------------------------------
/src/pid.h:
--------------------------------------------------------------------------------
1 | // Copyright 2025 Lukas Hrazky
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #pragma once
19 |
20 | #include "conf/datatypes.h"
21 | #include "imu.h"
22 | #include "motor_data.h"
23 |
24 | typedef struct {
25 | float p;
26 | float i;
27 | float rate_p; // used instead of d, works better with high Mahony KP
28 |
29 | // PID brake scaling
30 | float kp_brake_scale;
31 | float kp2_brake_scale;
32 | float kp_accel_scale;
33 | float kp2_accel_scale;
34 | } PID;
35 |
36 | void pid_init(PID *pid);
37 |
38 | void pid_update(
39 | PID *pid, float setpoint, const MotorData *md, const IMU *imu, const RefloatConfig *config
40 | );
41 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | # Refloat - VESC Package
2 | Refloat is a VESC Package for self-balancing skateboards. It aims to:
3 | - Provide a polished and full-featured user experience
4 | - Maintain a clean and reliable codebase that is easy to extend
5 | - Make it easy for anyone to use Refloat as a base for experimentation
6 | - Standardize interfaces so that package clones can interact with other parts of the ecosystem (3rd party apps, light modules, VESC Express addons etc.) in a compatible way
7 |
8 | _**If you're looking for README of the actual package, you can find it [here](package_README.md).**_
9 |
10 | ## Contributing
11 | Contributions are welcome and appreciated, please refer to [Contributing](CONTRIBUTING.md).
12 |
13 | ## Building
14 | ### Requirements
15 | - `gcc-arm-embedded` version 13 or higher
16 | - `make`
17 | - `vesc_tool`
18 |
19 | To build the package, run:
20 | ```sh
21 | make
22 | ```
23 |
24 | Note a new beta (as of writing this, unreleased) version of `vesc_tool` is needed for the above to work. To build the package with the current / old `vesc_tool` version, use:
25 | ```sh
26 | make OLDVT=1
27 | ```
28 |
29 | If you don't have `vesc_tool` in your `$PATH` (but you have, for example, a downloaded `vesc_tool` binary), you can specify the `vesc_tool` to use:
30 | ```sh
31 | make VESC_TOOL=/path/to/vesc_tool
32 | ```
33 |
34 | ## Documentation
35 | [Development Documentation](doc/index.md)
36 |
--------------------------------------------------------------------------------
/src/torque_tilt.h:
--------------------------------------------------------------------------------
1 | // Copyright 2022 Dado Mista
2 | // Copyright 2024 Lukas Hrazky
3 | //
4 | // This file is part of the Refloat VESC package.
5 | //
6 | // Refloat VESC package is free software: you can redistribute it and/or modify
7 | // it under the terms of the GNU General Public License as published by the
8 | // Free Software Foundation, either version 3 of the License, or (at your
9 | // option) any later version.
10 | //
11 | // Refloat VESC package is distributed in the hope that it will be useful, but
12 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
13 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
14 | // more details.
15 | //
16 | // You should have received a copy of the GNU General Public License along with
17 | // this program. If not, see .
18 |
19 | #pragma once
20 |
21 | #include "conf/datatypes.h"
22 | #include "motor_data.h"
23 |
24 | typedef struct {
25 | float on_step_size;
26 | float off_step_size;
27 |
28 | float ramped_step_size;
29 | float setpoint;
30 | } TorqueTilt;
31 |
32 | void torque_tilt_init(TorqueTilt *tt);
33 |
34 | void torque_tilt_reset(TorqueTilt *tt);
35 |
36 | void torque_tilt_configure(TorqueTilt *tt, const RefloatConfig *config);
37 |
38 | void torque_tilt_update(TorqueTilt *tt, const MotorData *motor, const RefloatConfig *config);
39 |
40 | void torque_tilt_winddown(TorqueTilt *tt);
41 |
--------------------------------------------------------------------------------
/Makefile:
--------------------------------------------------------------------------------
1 | # use `make VESC_TOOL=path/to/your/vesc_tool` to specify custom vesc_tool path
2 | VESC_TOOL ?= vesc_tool
3 | # use `make MINIFY_QML=0` to skip qml minification and pack the qml verbatim
4 | MINIFY_QML ?= 1
5 | # use `make OLDVT=1` to build with old vesc_tool which doesn't support pkgdesc.qml
6 | OLDVT ?= 0
7 |
8 | all: refloat.vescpkg
9 |
10 | refloat.vescpkg: src lisp/package.lisp package_README-gen.md ui.qml
11 | ifeq ($(OLDVT), 1)
12 | $(VESC_TOOL) --buildPkg "refloat.vescpkg:lisp/package.lisp:ui.qml:0:package_README-gen.md:Refloat"
13 | else
14 | $(VESC_TOOL) --buildPkgFromDesc pkgdesc.qml
15 | endif
16 |
17 | src:
18 | $(MAKE) -C $@
19 |
20 | VERSION=`cat version`
21 | PACKAGE_NAME=`cat package_name | cut -c-20`
22 |
23 | ifeq ($(strip $(MINIFY_QML)),1)
24 | MINIFY_CMD="./rjsmin.py"
25 | else
26 | MINIFY_CMD="cat"
27 | endif
28 |
29 | package_README-gen.md: package_README.md version
30 | cp $< $@
31 | echo "" >> $@
32 | echo "### Build Info" >> $@
33 | echo "- Version: ${VERSION}" >> $@
34 | echo "- Build Date: `date --rfc-3339=seconds`" >> $@
35 | echo "- Git Commit: #`git rev-parse --short HEAD`" >> $@
36 |
37 | ui.qml: ui.qml.in package_name version
38 | cat $< | \
39 | sed "s/{{PACKAGE_NAME}}/${PACKAGE_NAME}/g" | \
40 | sed "s/{{VERSION}}/${VERSION}/g" | \
41 | ${MINIFY_CMD} > $@
42 |
43 | clean:
44 | rm -f refloat.vescpkg package_README-gen.md ui.qml
45 | $(MAKE) -C src clean
46 |
47 | .PHONY: all clean src
48 |
--------------------------------------------------------------------------------
/src/charging.h:
--------------------------------------------------------------------------------
1 | // Copyright 2024 Lukas Hrazky
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #pragma once
19 |
20 | #include "state.h"
21 |
22 | #include
23 |
24 | typedef enum {
25 | COMMAND_CHARGING_STATE = 28, // to be called by ADV LCM while charging
26 | } ChargingCommands;
27 |
28 | typedef struct {
29 | float timer;
30 | float voltage;
31 | float current;
32 | } Charging;
33 |
34 | void charging_init(Charging *charging);
35 |
36 | void charging_timeout(Charging *charging, State *state);
37 |
38 | /**
39 | * Command to be called by ADV/LCM to announce that the board is charging.
40 | */
41 | void charging_state_request(Charging *charging, uint8_t *buffer, size_t len, State *state);
42 |
--------------------------------------------------------------------------------
/src/atr.h:
--------------------------------------------------------------------------------
1 | // Copyright 2022 Dado Mista
2 | // Copyright 2024 Lukas Hrazky
3 | //
4 | // This file is part of the Refloat VESC package.
5 | //
6 | // Refloat VESC package is free software: you can redistribute it and/or modify
7 | // it under the terms of the GNU General Public License as published by the
8 | // Free Software Foundation, either version 3 of the License, or (at your
9 | // option) any later version.
10 | //
11 | // Refloat VESC package is distributed in the hope that it will be useful, but
12 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
13 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
14 | // more details.
15 | //
16 | // You should have received a copy of the GNU General Public License along with
17 | // this program. If not, see .
18 |
19 | #pragma once
20 |
21 | #include "conf/datatypes.h"
22 | #include "motor_data.h"
23 |
24 | typedef struct {
25 | float on_step_size;
26 | float off_step_size;
27 | float speed_boost_mult;
28 |
29 | float accel_diff;
30 | float speed_boost;
31 |
32 | float target;
33 | float ramped_step_size;
34 | float setpoint;
35 | } ATR;
36 |
37 | void atr_init(ATR *atr);
38 |
39 | void atr_reset(ATR *atr);
40 |
41 | void atr_configure(ATR *atr, const RefloatConfig *config);
42 |
43 | void atr_update(ATR *atr, const MotorData *motor, const RefloatConfig *config);
44 |
45 | void atr_winddown(ATR *atr);
46 |
--------------------------------------------------------------------------------
/src/led_strip.h:
--------------------------------------------------------------------------------
1 | // Copyright 2025 Lukas Hrazky
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #pragma once
19 |
20 | #include "conf/datatypes.h"
21 |
22 | #include
23 |
24 | #define STRIP_COUNT 3
25 | #define LEDS_FRONT_AND_REAR_COUNT_MAX 60
26 |
27 | typedef struct {
28 | uint8_t map[LEDS_FRONT_AND_REAR_COUNT_MAX];
29 | } CipherData;
30 |
31 | typedef union {
32 | CipherData cipher;
33 | } TransitionData;
34 |
35 | typedef struct {
36 | uint32_t *data;
37 | uint8_t length;
38 | LedColorOrder color_order;
39 | bool reverse;
40 | float brightness;
41 | TransitionData trans_data;
42 | } LedStrip;
43 |
44 | void led_strip_init(LedStrip *strip);
45 |
46 | void led_strip_configure(LedStrip *strip, const CfgLedStrip *cfg);
47 |
--------------------------------------------------------------------------------
/src/brake_tilt.h:
--------------------------------------------------------------------------------
1 | // Copyright 2022 Dado Mista
2 | // Copyright 2024 Lukas Hrazky
3 | //
4 | // This file is part of the Refloat VESC package.
5 | //
6 | // Refloat VESC package is free software: you can redistribute it and/or modify
7 | // it under the terms of the GNU General Public License as published by the
8 | // Free Software Foundation, either version 3 of the License, or (at your
9 | // option) any later version.
10 | //
11 | // Refloat VESC package is distributed in the hope that it will be useful, but
12 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
13 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
14 | // more details.
15 | //
16 | // You should have received a copy of the GNU General Public License along with
17 | // this program. If not, see .
18 |
19 | #pragma once
20 |
21 | #include "atr.h"
22 | #include "conf/datatypes.h"
23 | #include "motor_data.h"
24 |
25 | typedef struct {
26 | float factor;
27 | float target;
28 | float ramped_step_size;
29 | float setpoint;
30 | } BrakeTilt;
31 |
32 | void brake_tilt_init(BrakeTilt *bt);
33 |
34 | void brake_tilt_reset(BrakeTilt *bt);
35 |
36 | void brake_tilt_configure(BrakeTilt *bt, const RefloatConfig *config);
37 |
38 | void brake_tilt_update(
39 | BrakeTilt *bt,
40 | const MotorData *motor,
41 | const ATR *atr,
42 | const RefloatConfig *config,
43 | float balance_offset
44 | );
45 |
46 | void brake_tilt_winddown(BrakeTilt *bt);
47 |
--------------------------------------------------------------------------------
/lisp/bms.lisp:
--------------------------------------------------------------------------------
1 | (defun bms-loop () {
2 | (var v-cell-support (eq (first (trap (get-bms-val 'bms-v-cell-min))) 'exit-ok))
3 | (var v-min 0)
4 | (var v-max 0)
5 | (var temp-min 0)
6 | (var temp-max 0)
7 | (var temp-fet -281)
8 | (loopwhile t {
9 | (if (and (>= (get-bms-val 'bms-can-id) 0) (ext-bms)) {
10 | (var msg-age (get-bms-val 'bms-msg-age))
11 | (setq temp-max (get-bms-val 'bms-temp-cell-max))
12 | (setq temp-min temp-max)
13 |
14 | (if v-cell-support {
15 | (if (= (get-bms-val 'bms-data-version) 1) {
16 | (setq temp-min (get-bms-val 'bms-temps-adc 1))
17 | (setq temp-fet (get-bms-val 'bms-temps-adc 3))
18 | })
19 | (setq v-min (get-bms-val 'bms-v-cell-min))
20 | (setq v-max (get-bms-val 'bms-v-cell-max))
21 | } {
22 | (var num-cells (get-bms-val 'bms-cell-num))
23 | (if (> num-cells 0) {
24 | (setq v-min (get-bms-val 'bms-v-cell 0))
25 | (setq v-max v-min)
26 | (looprange i 1 num-cells {
27 | (var cell-v (get-bms-val 'bms-v-cell i))
28 | (if (< cell-v v-min) (setq v-min cell-v))
29 | (if (> cell-v v-max) (setq v-max cell-v))
30 | })
31 | })
32 | })
33 | (ext-bms v-min v-max temp-min temp-max temp-fet msg-age)
34 | })
35 | (sleep 0.2)
36 | })
37 | })
38 |
--------------------------------------------------------------------------------
/doc/commands/float16.md:
--------------------------------------------------------------------------------
1 | # float16 Floating Point Number Representation
2 |
3 | `float16` is a 16-bit floating point representation compatible with the IEEE-754 FP16 format, with the difference that it doesn't support the `NaN` and `Inf` special numbers and instead uses the bit for doubling its range of representable numbers.
4 |
5 | It's used on the package interface to represent floating point numbers in a generic way at half the size of the standard 32-bit float, to save on bandwidth. Pretty much all realtime values in the package can be encoded in this representation without a significant precision impact (in case of needing very low or very high numbers, they should be scaled accordingly at the source).
6 |
7 | The format and the code are adopted from https://stackoverflow.com/a/60047308.
8 |
9 | Characteristics:
10 | - Dynamic range: +-131008.0
11 | - Normal numbers closest to zero: +-6.1035156E-5
12 | - Subnormal numbers closest to zero: +-5.9604645E-8
13 | - Precision: 3.311 decimal digits
14 |
15 | JavaScript snippet for decoding the `float16` representation encoded in an integer into a floating point value:
16 |
17 | ```js
18 | function float16_to_float(number) {
19 | var e = (number&0x7C00)>>10; // exponent
20 | var m16 = number&0x03FF; // original float16 mantissa
21 | var m = m16<<13; // new float 32 mantissa
22 | var v = m16>0 ? 140+Math.floor(Math.log2(m16)) : 0;
23 | // sign | normalized | denormalized
24 | var r = (number&0x8000)<<16 | (e!=0)*((e+112)<<23|m) | ((e==0)&(m!=0))*((v-37)<<23|((m<<(150-v))&0x007FE000));
25 | return new Float32Array(new Uint32Array([r]).buffer)[0];
26 | }
27 | ```
28 |
--------------------------------------------------------------------------------
/src/turn_tilt.h:
--------------------------------------------------------------------------------
1 | // Copyright 2025 Lukas Hrazky
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #pragma once
19 |
20 | #include "conf/datatypes.h"
21 | #include "imu.h"
22 | #include "motor_data.h"
23 |
24 | typedef struct {
25 | float step_size;
26 | float ramped_step_size;
27 | float boost_per_erpm;
28 |
29 | float last_yaw_angle;
30 | float last_yaw_change;
31 | float yaw_change;
32 | float abs_yaw_change;
33 | float yaw_aggregate;
34 |
35 | float target;
36 | float setpoint;
37 | } TurnTilt;
38 |
39 | void turn_tilt_init(TurnTilt *tt);
40 |
41 | void turn_tilt_reset(TurnTilt *tt);
42 |
43 | void turn_tilt_configure(TurnTilt *tt, const RefloatConfig *config);
44 |
45 | void turn_tilt_aggregate(TurnTilt *tt, const IMU *imu);
46 |
47 | void turn_tilt_update(TurnTilt *tt, const MotorData *md, const RefloatConfig *config);
48 |
49 | void turn_tilt_winddown(TurnTilt *tt);
50 |
--------------------------------------------------------------------------------
/src/balance_filter.h:
--------------------------------------------------------------------------------
1 | // Copyright 2023 - 2024 Lukas Hrazky
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #ifndef BALANCE_FILTER_h
19 | #define BALANCE_FILTER_h
20 |
21 | #include "conf/datatypes.h"
22 |
23 | typedef struct {
24 | float q0;
25 | float q1;
26 | float q2;
27 | float q3;
28 | float acc_mag;
29 |
30 | // parameters
31 | float kp_pitch;
32 | float kp_roll;
33 | float kp_yaw;
34 | } BalanceFilterData;
35 |
36 | void balance_filter_init(BalanceFilterData *data);
37 |
38 | void balance_filter_configure(BalanceFilterData *data, const RefloatConfig *config);
39 |
40 | void balance_filter_update(BalanceFilterData *data, float *gyro_xyz, float *accel_xyz, float dt);
41 |
42 | float balance_filter_get_roll(const BalanceFilterData *data);
43 | float balance_filter_get_pitch(const BalanceFilterData *data);
44 | float balance_filter_get_yaw(const BalanceFilterData *data);
45 |
46 | #endif
47 |
--------------------------------------------------------------------------------
/src/bms.h:
--------------------------------------------------------------------------------
1 | // Copyright 2024 Syler Clayton
2 | // Copyright 2025 Lukas Hrazky
3 | //
4 | // This file is part of the Refloat VESC package.
5 | //
6 | // Refloat VESC package is free software: you can redistribute it and/or modify
7 | // it under the terms of the GNU General Public License as published by the
8 | // Free Software Foundation, either version 3 of the License, or (at your
9 | // option) any later version.
10 | //
11 | // Refloat VESC package is distributed in the hope that it will be useful, but
12 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
13 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
14 | // more details.
15 | //
16 | // You should have received a copy of the GNU General Public License along with
17 | // this program. If not, see .
18 |
19 | #pragma once
20 |
21 | #include "conf/datatypes.h"
22 | #include "time.h"
23 |
24 | #include
25 | #include
26 |
27 | typedef enum {
28 | BMSF_NONE = 0,
29 | BMSF_CONNECTION = 1,
30 | BMSF_OVER_TEMP = 2,
31 | BMSF_CELL_OVER_VOLTAGE = 3,
32 | BMSF_CELL_UNDER_VOLTAGE = 4,
33 | BMSF_CELL_OVER_TEMP = 5,
34 | BMSF_CELL_UNDER_TEMP = 6,
35 | BMSF_CELL_BALANCE = 7
36 | } BMSFaultCode;
37 |
38 | typedef struct {
39 | float cell_lv;
40 | float cell_hv;
41 | int16_t cell_lt;
42 | int16_t cell_ht;
43 | int16_t bms_ht;
44 | float msg_age;
45 |
46 | uint32_t fault_mask;
47 | } BMS;
48 |
49 | void bms_init(BMS *bms);
50 |
51 | void bms_update(BMS *bms, const CfgBMS *cfg, const Time *time);
52 |
53 | bool bms_is_fault(const BMS *bms, BMSFaultCode fault_code);
54 |
--------------------------------------------------------------------------------
/src/data_recorder.h:
--------------------------------------------------------------------------------
1 | // Copyright 2024 Lukas Hrazky
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #pragma once
19 |
20 | #include "data.h"
21 | #include "data_record.h"
22 |
23 | #include
24 |
25 | // The data recorder is using a static buffer allocated in the VESC firmware to
26 | // record realtime data at the native loop frequency. It requires a special
27 | // firmware which reserves the buffer in memory and exposes the information
28 | // about it at the end of the VESC_IF memory area.
29 | //
30 | // See: /doc/realtime_value_tracking.md
31 |
32 | void data_recorder_init(DataRecord *dr);
33 |
34 | bool data_recorder_has_capability(const DataRecord *dr);
35 |
36 | void data_recorder_trigger(DataRecord *dr, bool engage);
37 |
38 | void data_recorder_sample(DataRecord *dr, const Data *data, time_t time);
39 |
40 | void data_recorder_request(DataRecord *dr, uint8_t *buffer, size_t len);
41 |
42 | void data_recorder_send_experiment_plot(DataRecord *dr);
43 |
--------------------------------------------------------------------------------
/src/time.c:
--------------------------------------------------------------------------------
1 | // Copyright 2024 Lukas Hrazky
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #include "time.h"
19 |
20 | static inline void time_now(Time *t) {
21 | if (VESC_IF->system_time_ticks) {
22 | t->now = VESC_IF->system_time_ticks();
23 | } else {
24 | t->now = VESC_IF->system_time() * SYSTEM_TICK_RATE_HZ;
25 | }
26 | }
27 |
28 | void time_init(Time *t) {
29 | time_now(t);
30 | t->start_timer = t->now;
31 | t->engage_timer = t->now;
32 | // Workaround: After startup (assume the time is very close to 0), we don't
33 | // want anything to be thinking we have just disengaged. Set disengage time
34 | // a minute into the past to prevent this.
35 | t->disengage_timer = t->now - 60;
36 | time_refresh_idle(t);
37 | }
38 |
39 | void time_update(Time *t, RunState state) {
40 | time_now(t);
41 | if (state == STATE_RUNNING) {
42 | t->disengage_timer = t->now;
43 | time_refresh_idle(t);
44 | }
45 | }
46 |
--------------------------------------------------------------------------------
/vesc_pkg_lib/utils/rb.h:
--------------------------------------------------------------------------------
1 | /*
2 | Copyright 2022 Benjamin Vedder benjamin@vedder.se
3 |
4 | This file is part of the VESC firmware.
5 |
6 | The VESC firmware is free software: you can redistribute it and/or modify
7 | it under the terms of the GNU General Public License as published by
8 | the Free Software Foundation, either version 3 of the License, or
9 | (at your option) any later version.
10 |
11 | The VESC firmware is distributed in the hope that it will be useful,
12 | but WITHOUT ANY WARRANTY; without even the implied warranty of
13 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14 | GNU General Public License for more details.
15 |
16 | You should have received a copy of the GNU General Public License
17 | along with this program. If not, see .
18 | */
19 |
20 | #ifndef RB_H_
21 | #define RB_H_
22 |
23 | #include
24 | #include
25 | #include "vesc_c_if.h"
26 |
27 | typedef struct {
28 | void *data;
29 | unsigned int head;
30 | unsigned int tail;
31 | unsigned int item_size;
32 | unsigned int item_count;
33 | lib_mutex mutex;
34 | bool full;
35 | } rb_t;
36 |
37 | void rb_init(rb_t *rb, void *buffer, int item_size, int item_count);
38 | void rb_init_alloc(rb_t *rb, int item_size, int item_count);
39 | void rb_free(rb_t *rb);
40 | void rb_flush(rb_t *rb);
41 | bool rb_insert(rb_t *rb, const void *data);
42 | unsigned int rb_insert_multi(rb_t *rb, const void *data, unsigned int count);
43 | bool rb_pop(rb_t *rb, void *data);
44 | unsigned int rb_pop_multi(rb_t *rb, void *data, unsigned int count);
45 | bool rb_is_full(rb_t *rb);
46 | bool rb_is_empty(rb_t *rb);
47 | unsigned int rb_get_item_count(rb_t *rb);
48 | unsigned int rb_get_free_space(rb_t *rb);
49 |
50 | #endif
51 |
52 |
--------------------------------------------------------------------------------
/vesc_pkg_lib/examples/thread/code.c:
--------------------------------------------------------------------------------
1 | /*
2 | Copyright 2022 Benjamin Vedder benjamin@vedder.se
3 |
4 | This file is part of the VESC firmware.
5 |
6 | The VESC firmware is free software: you can redistribute it and/or modify
7 | it under the terms of the GNU General Public License as published by
8 | the Free Software Foundation, either version 3 of the License, or
9 | (at your option) any later version.
10 |
11 | The VESC firmware is distributed in the hope that it will be useful,
12 | but WITHOUT ANY WARRANTY; without even the implied warranty of
13 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14 | GNU General Public License for more details.
15 |
16 | You should have received a copy of the GNU General Public License
17 | along with this program. If not, see .
18 | */
19 |
20 | #include "vesc_c_if.h"
21 |
22 | HEADER
23 |
24 | typedef struct {
25 | int a;
26 | int b;
27 | lib_thread thread;
28 | } data;
29 |
30 | static void thd(void *arg) {
31 | data *d = (data*)arg;
32 |
33 | while (!VESC_IF->should_terminate()) {
34 | VESC_IF->printf("Hello Thd");
35 | d->b++;
36 | VESC_IF->sleep_ms(1000);
37 | }
38 | }
39 |
40 | // Called when code is stopped
41 | static void stop(void *arg) {
42 | data *d = (data*)arg;
43 | VESC_IF->printf("a: %d, b: %d", d->a, d->b);
44 | VESC_IF->request_terminate(d->thread);
45 | VESC_IF->printf("Terminated");
46 | VESC_IF->free(d);
47 | }
48 |
49 | INIT_FUN(lib_info *info) {
50 | INIT_START
51 |
52 | data *d = VESC_IF->malloc(sizeof(data));
53 | d->a = 5;
54 | d->b = 6;
55 | d->thread = VESC_IF->spawn(thd, 1024, "LibThd", d);
56 |
57 | info->stop_fun = stop;
58 | info->arg = d;
59 |
60 | VESC_IF->printf("Hello Example!");
61 |
62 | return true;
63 | }
64 |
65 |
--------------------------------------------------------------------------------
/src/haptic_feedback.h:
--------------------------------------------------------------------------------
1 | // Copyright 2024 Lukas Hrazky
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #pragma once
19 |
20 | #include "conf/datatypes.h"
21 | #include "motor_control.h"
22 | #include "motor_data.h"
23 | #include "state.h"
24 | #include "time.h"
25 |
26 | typedef enum {
27 | HAPTIC_FEEDBACK_NONE = 0,
28 | HAPTIC_FEEDBACK_DUTY_SPEED,
29 | HAPTIC_FEEDBACK_DUTY_CONTINUOUS,
30 | HAPTIC_FEEDBACK_ERROR_TEMPERATURE,
31 | HAPTIC_FEEDBACK_ERROR_VOLTAGE,
32 | HAPTIC_FEEDBACK_ERROR_FATAL,
33 | } HapticFeedbackType;
34 |
35 | typedef struct {
36 | const CfgHapticFeedback *cfg;
37 | float duty_solid_threshold;
38 | float str_poly_b;
39 | float str_poly_c;
40 |
41 | HapticFeedbackType type_playing;
42 | time_t tone_timer;
43 | bool is_playing;
44 | bool can_change_type;
45 | } HapticFeedback;
46 |
47 | void haptic_feedback_init(HapticFeedback *hf);
48 |
49 | void haptic_feedback_configure(HapticFeedback *hf, const RefloatConfig *cfg);
50 |
51 | void haptic_feedback_update(
52 | HapticFeedback *hf,
53 | MotorControl *mc,
54 | const State *state,
55 | const MotorData *md,
56 | const AlertTracker *at,
57 | const Time *time
58 | );
59 |
--------------------------------------------------------------------------------
/src/biquad.c:
--------------------------------------------------------------------------------
1 | // Copyright 2022 Benjamin Vedder
2 | // Copyright 2024 Lukas Hrazky
3 | //
4 | // This file is part of the Refloat VESC package.
5 | //
6 | // Refloat VESC package is free software: you can redistribute it and/or modify
7 | // it under the terms of the GNU General Public License as published by the
8 | // Free Software Foundation, either version 3 of the License, or (at your
9 | // option) any later version.
10 | //
11 | // Refloat VESC package is distributed in the hope that it will be useful, but
12 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
13 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
14 | // more details.
15 | //
16 | // You should have received a copy of the GNU General Public License along with
17 | // this program. If not, see .
18 |
19 | #include "biquad.h"
20 |
21 | #include
22 |
23 | float biquad_process(Biquad *biquad, float in) {
24 | float out = in * biquad->a0 + biquad->z1;
25 | biquad->z1 = in * biquad->a1 + biquad->z2 - biquad->b1 * out;
26 | biquad->z2 = in * biquad->a2 - biquad->b2 * out;
27 | return out;
28 | }
29 |
30 | void biquad_configure(Biquad *biquad, BiquadType type, float frequency) {
31 | float K = tanf(M_PI * frequency);
32 | float Q = 0.707; // maximum sharpness (0.5 = maximum smoothness)
33 | float norm = 1 / (1 + K / Q + K * K);
34 | if (type == BQ_LOWPASS) {
35 | biquad->a0 = K * K * norm;
36 | biquad->a1 = 2 * biquad->a0;
37 | biquad->a2 = biquad->a0;
38 | } else if (type == BQ_HIGHPASS) {
39 | biquad->a0 = 1 * norm;
40 | biquad->a1 = -2 * biquad->a0;
41 | biquad->a2 = biquad->a0;
42 | }
43 | biquad->b1 = 2 * (K * K - 1) * norm;
44 | biquad->b2 = (1 - K / Q + K * K) * norm;
45 | }
46 |
47 | void biquad_reset(Biquad *biquad) {
48 | biquad->z1 = 0;
49 | biquad->z2 = 0;
50 | }
51 |
--------------------------------------------------------------------------------
/src/Makefile:
--------------------------------------------------------------------------------
1 | # WARNING: If you use this Makefile to build, you need to generate config files
2 | # from settings.xml using this file as well, otherwise Refloat Cfg will not
3 | # load in vesc_tool, see comment below.
4 |
5 | VESC_TOOL ?= vesc_tool
6 |
7 | TARGET = package_lib
8 |
9 | all: $(TARGET)
10 |
11 | REFLOAT_SOURCES = $(wildcard *.c) $(wildcard lib/*.c)
12 | CONF_GEN_HEADERS = conf/conf_default.h conf/confparser.h conf/confxml.h
13 | CONF_GEN_SOURCES = conf/confparser.c conf/confxml.c
14 | CONF_GEN_FILES = $(CONF_GEN_HEADERS) $(CONF_GEN_SOURCES)
15 | SOURCES = $(REFLOAT_SOURCES) $(CONF_GEN_SOURCES) conf/buffer.c
16 | DEPS = $(SOURCES:.c=.d)
17 |
18 | ADD_TO_CLEAN = $(CONF_GEN_FILES) $(DEPS) conf/conf_general.h
19 |
20 | VESC_C_LIB_PATH = ../vesc_pkg_lib/
21 | include $(VESC_C_LIB_PATH)rules.mk
22 |
23 | CFLAGS += -MMD -flto
24 | LDFLAGS += -flto
25 |
26 | $(REFLOAT_SOURCES): $(CONF_GEN_HEADERS) conf/conf_general.h
27 |
28 | $(CONF_GEN_FILES) &: conf/settings.xml
29 | $(VESC_TOOL) --xmlConfToCode conf/settings.xml
30 | # !!! make xml config loading in vesc_tool work with LTO !!!
31 | sed -i "s/^uint8_t data_/__attribute__((used)) uint8_t data_/g" conf/confxml.c
32 |
33 | PACKAGE_NAME=`cat ../package_name | cut -c-20`
34 | VERSION=`cat ../version`
35 | MAJOR=`cat ../version | cut -d. -f1`
36 | MINOR=`cat ../version | cut -d. -f2`
37 | PATCH=`cat ../version | cut -d. -f3 | cut -d- -f1`
38 | SUFFIX=`cat ../version | cut -d. -f3 | cut -d- -f2- | cut -c-20`
39 | GIT_HASH=`git rev-parse --short=8 HEAD | cut -c-8`
40 |
41 | conf/conf_general.h: conf/conf_general.h.in ../package_name ../version
42 | cat $< | \
43 | sed "s/{{PACKAGE_NAME}}/${PACKAGE_NAME}/g" | \
44 | sed "s/{{VERSION}}/${VERSION}/g" | \
45 | sed "s/{{MAJOR_VERSION}}/${MAJOR}/g" | \
46 | sed "s/{{MINOR_VERSION}}/${MINOR}/g" | \
47 | sed "s/{{PATCH_VERSION}}/${PATCH}/g" | \
48 | sed "s/{{VERSION_SUFFIX}}/${SUFFIX}/g" | \
49 | sed "s/{{GIT_HASH}}/${GIT_HASH}/g" > $@
50 |
51 | -include $(DEPS)
52 |
--------------------------------------------------------------------------------
/changelog.py:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python
2 |
3 | from argparse import ArgumentParser
4 | import git
5 | import re
6 |
7 |
8 | maintainer = "lukkash@email.cz"
9 |
10 |
11 | def format_entry(entry, author):
12 | entry = re.sub(" +> +", "\n \n ", entry)
13 |
14 | if author.email != maintainer:
15 | if "\n" in entry:
16 | return entry.replace("\n", " [{}]\n".format(author.name), 1)
17 | else:
18 | return entry + " [{}]".format(author.name)
19 |
20 | return entry
21 |
22 |
23 | def main():
24 | parser = ArgumentParser(prog='changelog')
25 | args = parser.parse_args()
26 |
27 | repo = git.Repo(".", search_parent_directories=True)
28 |
29 | tagmap = {}
30 | for t in repo.tags:
31 | tagmap.setdefault(repo.commit(t), []).append(t)
32 |
33 | def ref_tag(commit):
34 | for tag in tagmap.get(commit, tuple()):
35 | if re.match("^v[0-9]+\.[0-9]+\.[0-9]+.*", tag.name):
36 | return tag
37 |
38 | return None
39 |
40 | first_version = ref_tag(repo.head.commit)
41 |
42 | features = []
43 | fixes = []
44 | for commit in repo.iter_commits():
45 | if commit != repo.head.commit:
46 | tag = ref_tag(commit)
47 | if tag is not None:
48 | break
49 |
50 | if commit.trailers:
51 | if "Feature" in commit.trailers:
52 | features.append(format_entry(commit.trailers["Feature"], commit.author))
53 |
54 | if "Fix" in commit.trailers:
55 | fixes.append(format_entry(commit.trailers["Fix"], commit.author))
56 |
57 | def print_list(lst):
58 | for entry in reversed(lst):
59 | print("- {}\n".format(entry))
60 |
61 | if features:
62 | print("### Features")
63 | print_list(features)
64 |
65 | if fixes:
66 | print("### Fixes")
67 | print_list(fixes)
68 |
69 |
70 | if __name__ == '__main__':
71 | main()
72 |
--------------------------------------------------------------------------------
/src/motor_control.h:
--------------------------------------------------------------------------------
1 | // Copyright 2024 Lukas Hrazky
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #pragma once
19 |
20 | #include
21 | #include
22 |
23 | #include "conf/datatypes.h"
24 | #include "state.h"
25 | #include "time.h"
26 |
27 | typedef struct {
28 | bool disabled;
29 | bool current_requested;
30 | float requested_current;
31 |
32 | uint8_t click_counter;
33 | time_t brake_timer;
34 | bool parking_brake_active;
35 |
36 | uint8_t tone_ticks;
37 | uint8_t tone_counter;
38 | bool tone_high;
39 | float tone_intensity;
40 |
41 | float brake_current;
42 | float click_current;
43 | ParkingBrakeMode parking_brake_mode;
44 | uint16_t main_freq;
45 | } MotorControl;
46 |
47 | void motor_control_init(MotorControl *mc);
48 |
49 | void motor_control_configure(MotorControl *mc, const RefloatConfig *config);
50 |
51 | void motor_control_request_current(MotorControl *mc, float current);
52 |
53 | void motor_control_apply(MotorControl *mc, float abs_erpm, RunState state, const Time *time);
54 |
55 | void motor_control_play_tone(MotorControl *mc, uint16_t frequency, float intensity);
56 |
57 | void motor_control_stop_tone(MotorControl *mc);
58 |
59 | void motor_control_play_click(MotorControl *mc);
60 |
--------------------------------------------------------------------------------
/src/konami.c:
--------------------------------------------------------------------------------
1 | // Copyright 2024 Lukas Hrazky
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #include "konami.h"
19 |
20 | void konami_init(Konami *konami, const FootpadSensorState *sequence, uint8_t sequence_size) {
21 | konami->timer = 0;
22 | konami->state = 0;
23 | konami->sequence = sequence;
24 | konami->sequence_size = sequence_size;
25 | }
26 |
27 | static void konami_reset(Konami *konami) {
28 | konami->state = 0;
29 | }
30 |
31 | bool konami_check(Konami *konami, Leds *leds, const FootpadSensor *fs, const Time *time) {
32 | if (konami->state > 0 && timer_older(time, konami->timer, 0.5)) {
33 | konami_reset(konami);
34 | return false;
35 | }
36 |
37 | if (fs->state == konami->sequence[konami->state]) {
38 | if (timer_older(time, konami->timer, 0.15)) {
39 | ++konami->state;
40 | if (konami->state == konami->sequence_size) {
41 | konami_reset(konami);
42 | leds_status_confirm(leds);
43 | return true;
44 | }
45 |
46 | timer_refresh(time, &konami->timer);
47 | }
48 | } else if (konami->state > 0 && fs->state != konami->sequence[konami->state - 1]) {
49 | konami_reset(konami);
50 | }
51 |
52 | return false;
53 | }
54 |
--------------------------------------------------------------------------------
/src/led_driver.h:
--------------------------------------------------------------------------------
1 | // Copyright 2022 Benjamin Vedder
2 | // Copyright 2024 Lukas Hrazky
3 | //
4 | // This file is part of the Refloat VESC package.
5 | //
6 | // Refloat VESC package is free software: you can redistribute it and/or modify
7 | // it under the terms of the GNU General Public License as published by the
8 | // Free Software Foundation, either version 3 of the License, or (at your
9 | // option) any later version.
10 | //
11 | // Refloat VESC package is distributed in the hope that it will be useful, but
12 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
13 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
14 | // more details.
15 | //
16 | // You should have received a copy of the GNU General Public License along with
17 | // this program. If not, see .
18 |
19 | #pragma once
20 |
21 | #include "conf/datatypes.h"
22 | #include "led_strip.h"
23 |
24 | #include "st_types.h"
25 |
26 | #include
27 | #include
28 |
29 | typedef struct {
30 | void *pin_port;
31 | TIM_TypeDef *timer;
32 | uint32_t ccr_address;
33 | uint32_t rcc_apb1_periph;
34 | volatile uint32_t *timer_ccmr;
35 | DMA_Stream_TypeDef *dma_stream;
36 | uint32_t dma_channel;
37 | uint16_t dma_source;
38 | uint8_t dma_if_shift;
39 | uint8_t timer_ccmr_shift;
40 | uint8_t timer_ccer_shift;
41 | uint8_t pin_nr;
42 | } PinHwConfig;
43 |
44 | typedef struct {
45 | uint16_t *bitbuffer;
46 | uint32_t bitbuffer_length;
47 | LedPin pin;
48 | const PinHwConfig *pin_hw_config;
49 | const LedStrip *strips[STRIP_COUNT];
50 | uint16_t *strip_bitbuffs[STRIP_COUNT];
51 | } LedDriver;
52 |
53 | void led_driver_init(LedDriver *driver);
54 |
55 | bool led_driver_setup(
56 | LedDriver *driver, LedPin pin, LedPinConfig pin_config, const LedStrip **led_strips
57 | );
58 |
59 | void led_driver_paint(LedDriver *driver);
60 |
61 | void led_driver_destroy(LedDriver *driver);
62 |
--------------------------------------------------------------------------------
/vesc_pkg_lib/examples/config/conf/buffer.h:
--------------------------------------------------------------------------------
1 | /*
2 | Copyright 2016 Benjamin Vedder benjamin@vedder.se
3 |
4 | This file is part of the VESC firmware.
5 |
6 | The VESC firmware is free software: you can redistribute it and/or modify
7 | it under the terms of the GNU General Public License as published by
8 | the Free Software Foundation, either version 3 of the License, or
9 | (at your option) any later version.
10 |
11 | The VESC firmware is distributed in the hope that it will be useful,
12 | but WITHOUT ANY WARRANTY; without even the implied warranty of
13 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14 | GNU General Public License for more details.
15 |
16 | You should have received a copy of the GNU General Public License
17 | along with this program. If not, see .
18 | */
19 |
20 | #ifndef BUFFER_H_
21 | #define BUFFER_H_
22 |
23 | #include
24 |
25 | void buffer_append_int16(uint8_t* buffer, int16_t number, int32_t *index);
26 | void buffer_append_uint16(uint8_t* buffer, uint16_t number, int32_t *index);
27 | void buffer_append_int32(uint8_t* buffer, int32_t number, int32_t *index);
28 | void buffer_append_uint32(uint8_t* buffer, uint32_t number, int32_t *index);
29 | void buffer_append_float16(uint8_t* buffer, float number, float scale, int32_t *index);
30 | void buffer_append_float32(uint8_t* buffer, float number, float scale, int32_t *index);
31 | void buffer_append_float32_auto(uint8_t* buffer, float number, int32_t *index);
32 | int16_t buffer_get_int16(const uint8_t *buffer, int32_t *index);
33 | uint16_t buffer_get_uint16(const uint8_t *buffer, int32_t *index);
34 | int32_t buffer_get_int32(const uint8_t *buffer, int32_t *index);
35 | uint32_t buffer_get_uint32(const uint8_t *buffer, int32_t *index);
36 | float buffer_get_float16(const uint8_t *buffer, float scale, int32_t *index);
37 | float buffer_get_float32(const uint8_t *buffer, float scale, int32_t *index);
38 | float buffer_get_float32_auto(const uint8_t *buffer, int32_t *index);
39 |
40 | #endif /* BUFFER_H_ */
41 |
--------------------------------------------------------------------------------
/vesc_pkg_lib/examples/custom_data_comm/buffer.h:
--------------------------------------------------------------------------------
1 | /*
2 | Copyright 2016 Benjamin Vedder benjamin@vedder.se
3 |
4 | This file is part of the VESC firmware.
5 |
6 | The VESC firmware is free software: you can redistribute it and/or modify
7 | it under the terms of the GNU General Public License as published by
8 | the Free Software Foundation, either version 3 of the License, or
9 | (at your option) any later version.
10 |
11 | The VESC firmware is distributed in the hope that it will be useful,
12 | but WITHOUT ANY WARRANTY; without even the implied warranty of
13 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14 | GNU General Public License for more details.
15 |
16 | You should have received a copy of the GNU General Public License
17 | along with this program. If not, see .
18 | */
19 |
20 | #ifndef BUFFER_H_
21 | #define BUFFER_H_
22 |
23 | #include
24 |
25 | void buffer_append_int16(uint8_t* buffer, int16_t number, int32_t *index);
26 | void buffer_append_uint16(uint8_t* buffer, uint16_t number, int32_t *index);
27 | void buffer_append_int32(uint8_t* buffer, int32_t number, int32_t *index);
28 | void buffer_append_uint32(uint8_t* buffer, uint32_t number, int32_t *index);
29 | void buffer_append_float16(uint8_t* buffer, float number, float scale, int32_t *index);
30 | void buffer_append_float32(uint8_t* buffer, float number, float scale, int32_t *index);
31 | void buffer_append_float32_auto(uint8_t* buffer, float number, int32_t *index);
32 | int16_t buffer_get_int16(const uint8_t *buffer, int32_t *index);
33 | uint16_t buffer_get_uint16(const uint8_t *buffer, int32_t *index);
34 | int32_t buffer_get_int32(const uint8_t *buffer, int32_t *index);
35 | uint32_t buffer_get_uint32(const uint8_t *buffer, int32_t *index);
36 | float buffer_get_float16(const uint8_t *buffer, float scale, int32_t *index);
37 | float buffer_get_float32(const uint8_t *buffer, float scale, int32_t *index);
38 | float buffer_get_float32_auto(const uint8_t *buffer, int32_t *index);
39 |
40 | #endif /* BUFFER_H_ */
41 |
--------------------------------------------------------------------------------
/vesc_pkg_lib/rules.mk:
--------------------------------------------------------------------------------
1 |
2 | CC = arm-none-eabi-gcc
3 | LD = arm-none-eabi-gcc
4 | OBJDUMP = arm-none-eabi-objdump
5 | OBJCOPY = arm-none-eabi-objcopy
6 | PYTHON = python3
7 |
8 | STLIB_PATH = $(VESC_C_LIB_PATH)/stdperiph_stm32f4/
9 |
10 | ifeq ($(USE_STLIB),yes)
11 | SOURCES += \
12 | $(STLIB_PATH)/src/misc.c \
13 | $(STLIB_PATH)/src/stm32f4xx_adc.c \
14 | $(STLIB_PATH)/src/stm32f4xx_dma.c \
15 | $(STLIB_PATH)/src/stm32f4xx_exti.c \
16 | $(STLIB_PATH)/src/stm32f4xx_flash.c \
17 | $(STLIB_PATH)/src/stm32f4xx_rcc.c \
18 | $(STLIB_PATH)/src/stm32f4xx_syscfg.c \
19 | $(STLIB_PATH)/src/stm32f4xx_tim.c \
20 | $(STLIB_PATH)/src/stm32f4xx_iwdg.c \
21 | $(STLIB_PATH)/src/stm32f4xx_wwdg.c
22 | endif
23 |
24 | UTILS_PATH = $(VESC_C_LIB_PATH)/utils/
25 |
26 | SOURCES += $(UTILS_PATH)/rb.c
27 | SOURCES += $(UTILS_PATH)/utils.c
28 |
29 | OBJECTS = $(SOURCES:.c=.so)
30 |
31 | ifeq ($(USE_OPT),)
32 | USE_OPT =
33 | endif
34 |
35 | CFLAGS = -fpic -Os -Wall -Wextra -Wundef -std=gnu99 -I$(VESC_C_LIB_PATH)
36 | CFLAGS += -I$(STLIB_PATH)/CMSIS/include -I$(STLIB_PATH)/CMSIS/ST -I$(STLIB_PATH)/inc -I$(UTILS_PATH)/
37 | CFLAGS += -fomit-frame-pointer -falign-functions=16 -mthumb
38 | CFLAGS += -fsingle-precision-constant -Wdouble-promotion
39 | CFLAGS += -mfloat-abi=hard -mfpu=fpv4-sp-d16 -mcpu=cortex-m4
40 | CFLAGS += -fdata-sections -ffunction-sections
41 | CFLAGS += -DIS_VESC_LIB
42 | CFLAGS += $(USE_OPT)
43 |
44 | ifeq ($(USE_STLIB),yes)
45 | CFLAGS += -DUSE_STLIB
46 | endif
47 |
48 | LDFLAGS = -nostartfiles -static -mfloat-abi=hard -mfpu=fpv4-sp-d16 -mcpu=cortex-m4
49 | LDFLAGS += -lm -Wl,--gc-sections,--undefined=init
50 | LDFLAGS += -T $(VESC_C_LIB_PATH)/link.ld
51 |
52 | .PHONY: default all clean
53 |
54 | default: $(TARGET)
55 | all: default
56 |
57 | %.so: %.c
58 | $(CC) $(CFLAGS) -c $< -o $@
59 |
60 | .PRECIOUS: $(TARGET) $(OBJECTS)
61 |
62 | $(TARGET): $(OBJECTS)
63 | $(LD) $(OBJECTS) $(LDFLAGS) -o $@.elf
64 | $(OBJDUMP) -D $@.elf > $@.list
65 | $(OBJCOPY) -O binary $@.elf $@.bin --gap-fill 0x00
66 | $(PYTHON) $(VESC_C_LIB_PATH)/conv.py -f $@.bin -n $@ > $@.lisp
67 |
68 | clean:
69 | rm -f $(OBJECTS) $(TARGET).elf $(TARGET).list $(TARGET).lisp $(TARGET).bin $(ADD_TO_CLEAN)
70 |
--------------------------------------------------------------------------------
/src/charging.c:
--------------------------------------------------------------------------------
1 | // Copyright 2024 Lukas Hrazky
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #include "charging.h"
19 |
20 | #include "conf/buffer.h"
21 |
22 | #include "vesc_c_if.h"
23 |
24 | void charging_init(Charging *charging) {
25 | charging->timer = 0.0f;
26 | charging->voltage = 0.0f;
27 | charging->current = 0.0f;
28 | }
29 |
30 | void charging_timeout(Charging *charging, State *state) {
31 | // Timeout the charging state after 5 seconds if the charging module didn't update
32 | if (VESC_IF->system_time() - charging->timer > 5.0f) {
33 | state->charging = false;
34 | }
35 | }
36 |
37 | void charging_state_request(Charging *charging, uint8_t *buffer, size_t len, State *state) {
38 | // Expecting 6 bytes:
39 | // -magic nr: must be 151
40 | // -charging: 1/0 aka true/false
41 | // -voltage: 16bit float divided by 10
42 | // -current: 16bit float divided by 10
43 | if (len < 6) {
44 | return;
45 | }
46 | int32_t idx = 0;
47 |
48 | uint8_t magicnr = buffer[idx++];
49 | if (magicnr != 151) {
50 | return;
51 | }
52 |
53 | state->charging = buffer[idx++] > 0;
54 | charging->timer = VESC_IF->system_time();
55 |
56 | if (state->charging) {
57 | charging->voltage = buffer_get_float16(buffer, 10, &idx);
58 | charging->current = buffer_get_float16(buffer, 10, &idx);
59 | } else {
60 | charging->voltage = 0;
61 | charging->current = 0;
62 | }
63 | }
64 |
--------------------------------------------------------------------------------
/src/time.h:
--------------------------------------------------------------------------------
1 | // Copyright 2024 Lukas Hrazky
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #pragma once
19 |
20 | #include "state.h"
21 |
22 | #include "vesc_c_if.h"
23 |
24 | typedef uint32_t time_t;
25 |
26 | typedef struct {
27 | time_t now;
28 | time_t start_timer;
29 | time_t engage_timer;
30 | time_t disengage_timer;
31 | time_t idle_timer;
32 | } Time;
33 |
34 | void time_init(Time *t);
35 |
36 | void time_update(Time *t, RunState state);
37 |
38 | inline void time_refresh_idle(Time *t) {
39 | t->idle_timer = t->now;
40 | }
41 |
42 | inline void timer_refresh(const Time *t, time_t *timer) {
43 | *timer = t->now;
44 | }
45 |
46 | inline bool timer_older(const Time *t, time_t timer, float seconds) {
47 | return t->now - timer > (time_t) (seconds * SYSTEM_TICK_RATE_HZ);
48 | }
49 |
50 | inline bool timer_older_ms(const Time *t, time_t timer, float seconds) {
51 | return t->now - timer > (time_t) (seconds * SYSTEM_TICK_RATE_HZ / 1000);
52 | }
53 |
54 | inline float timer_age(const Time *t, time_t timer) {
55 | return (t->now - timer) * (1.0f / SYSTEM_TICK_RATE_HZ);
56 | }
57 |
58 | #define time_elapsed(t, event, seconds) \
59 | ({ \
60 | const Time *_t = (t); \
61 | timer_older(_t, _t->event##_timer, seconds); \
62 | })
63 |
--------------------------------------------------------------------------------
/src/alert_tracker.h:
--------------------------------------------------------------------------------
1 | // Copyright 2025 Lukas Hrazky
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #pragma once
19 |
20 | #include "conf/datatypes.h"
21 | #include "lib/circular_buffer.h"
22 | #include "time.h"
23 |
24 | #define ALERT_TRACKER_SIZE 20
25 |
26 | typedef enum {
27 | ATYPE_FATAL = 1,
28 | ATYPE_ERROR = 2,
29 | ATYPE_WARNING = 3,
30 | } AlertType;
31 |
32 | typedef enum {
33 | ALERT_NONE = 0,
34 | ALERT_FW_FAULT = 1,
35 | ALERT_LAST = ALERT_FW_FAULT
36 | } AlertId;
37 |
38 | typedef struct {
39 | uint8_t type;
40 | } AlertProperties;
41 |
42 | typedef struct {
43 | time_t time;
44 | uint8_t id;
45 | bool active;
46 | uint8_t code;
47 | } AlertRecord;
48 |
49 | typedef struct {
50 | bool persistent_fatal_error;
51 |
52 | uint32_t active_alert_mask;
53 | uint32_t new_active_alert_mask;
54 | mc_fault_code fw_fault_code;
55 | bool fatal_error;
56 |
57 | uint8_t alert_buffer_array[ALERT_TRACKER_SIZE * sizeof(AlertRecord)];
58 | CircularBuffer alert_buffer;
59 | } AlertTracker;
60 |
61 | const AlertProperties *alert_tracker_properties(AlertId alert_id);
62 |
63 | void alert_tracker_init(AlertTracker *at);
64 |
65 | void alert_tracker_configure(AlertTracker *at, const RefloatConfig *config);
66 |
67 | void alert_tracker_add(AlertTracker *at, const Time *time, uint8_t id, uint8_t data);
68 |
69 | void alert_tracker_finalize(AlertTracker *at, const Time *time);
70 |
71 | bool alert_tracker_is_alert_active(AlertTracker *at, AlertId alert);
72 |
73 | void alert_tracker_clear_fatal(AlertTracker *at);
74 |
--------------------------------------------------------------------------------
/package_README.md:
--------------------------------------------------------------------------------
1 | # Refloat
2 |
3 | A full-featured self-balancing skateboard package.
4 |
5 | ## New in 1.2
6 | - BMS alerting support (Pushback and Haptic)
7 | - Speed-based alerting (Pushback and Haptic)
8 | - Automatic config migration when updating the package
9 | - Support for per-cell High/Low Voltage Thresholds (no more needing to adjust them in Specs after a fresh install, 6.05+ only)
10 | - Groundworks for a new alerting system, for now only providing firmware fault reporting
11 | - New Rainbow Fade, Rainbow Cycle and Rainbow Roll LED effects
12 |
13 | For more details, read the [1.2 release post](https://pev.dev/t/refloat-version-1-2/2795).
14 |
15 | ## Installation
16 | ### Upgrading
17 | Back up your package config (either by **Backup Configs** on the Start page, or by saving the XML on **Refloat Cfg**).
18 |
19 | If upgrading from Refloat 1.1 to 1.2, an automatic config restore dialog should pop up. Confirm it to restore. This is the preferred way to update the config from now on, as it will also migrate any changed options to the new version. Other methods of restoring the config will not do that.
20 |
21 | In case the automatic config restore fails, restore it the traditional way and please report the issue, so that it can be fixed.
22 |
23 | ### Fresh Installation
24 | If doing a fresh board installation, you need to do the **motor** and **IMU** calibration and configuration. If you install the package before that, you need to disable the package before running the **motor** _calibration_ and re-enable it afterwards.
25 |
26 | For a detailed guide, read the [Initial Board Setup guide on pev.dev](https://pev.dev/t/initial-board-setup-in-vesc-tool/2190).
27 |
28 | On 6.05+ firmware, the package should ride well without the need to configure anything in Refloat Cfg. On 6.02, the **Low and High Tiltback voltages** on the **Specs** tab of **Refloat Cfg** still need to be set according to your battery specs.
29 |
30 | ## Disclaimer
31 | **Use at your own risk!** Electric vehicles are inherently dangerous, authors of this package shall not be liable for any damage or harm caused by errors in the software. Not endorsed by the VESC project.
32 |
33 | ## Credits
34 | Author: Lukáš Hrázký
35 |
36 | Original Float package authors: Mitch Lustig, Dado Mista, Nico Aleman
37 |
38 | ## Downloads and Changelogs
39 | [https://github.com/lukash/refloat/releases](https://github.com/lukash/refloat/releases)
40 |
--------------------------------------------------------------------------------
/vesc_pkg_lib/examples/custom_data_comm/qml.qml:
--------------------------------------------------------------------------------
1 | /*
2 | Copyright 2022 Benjamin Vedder benjamin@vedder.se
3 |
4 | This file is part of the VESC firmware.
5 |
6 | The VESC firmware is free software: you can redistribute it and/or modify
7 | it under the terms of the GNU General Public License as published by
8 | the Free Software Foundation, either version 3 of the License, or
9 | (at your option) any later version.
10 |
11 | The VESC firmware is distributed in the hope that it will be useful,
12 | but WITHOUT ANY WARRANTY; without even the implied warranty of
13 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14 | GNU General Public License for more details.
15 |
16 | You should have received a copy of the GNU General Public License
17 | along with this program. If not, see .
18 | */
19 |
20 | import QtQuick 2.5
21 | import QtQuick.Controls 2.2
22 | import QtQuick.Layouts 1.3
23 |
24 | import Vedder.vesc.commands 1.0
25 | import Vedder.vesc.configparams 1.0
26 |
27 | Item {
28 | id: container
29 | anchors.fill: parent
30 | anchors.margins: 10
31 |
32 | property Commands mCommands: VescIf.commands()
33 |
34 | ColumnLayout {
35 | anchors.fill: parent
36 |
37 | DoubleSpinBox {
38 | id: sb
39 | Layout.fillWidth: true
40 | }
41 |
42 | Item {
43 | Layout.fillHeight: true
44 | }
45 | }
46 |
47 | // Send the value of the spinbox every second
48 | Timer {
49 | running: true
50 | repeat: true
51 | interval: 1000
52 |
53 | onTriggered: {
54 | var buffer = new ArrayBuffer(4)
55 | var dv = new DataView(buffer)
56 | var ind = 0
57 | dv.setFloat32(ind, sb.realValue); ind += 4
58 | mCommands.sendCustomAppData(buffer)
59 | }
60 | }
61 |
62 | // Print the message counter and value that we sent the last time
63 | Connections {
64 | target: mCommands
65 |
66 | onCustomAppDataReceived: {
67 | var dv = new DataView(data)
68 | var ind = 0
69 | var msg_cnt = dv.getInt32(ind); ind += 4
70 | var msg_val = dv.getFloat32(ind); ind += 4
71 | console.log(msg_cnt + " " + msg_val)
72 | }
73 | }
74 | }
75 |
--------------------------------------------------------------------------------
/src/conf/buffer.h:
--------------------------------------------------------------------------------
1 | // Copyright 2022 Benjamin Vedder
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #ifndef BUFFER_H_
19 | #define BUFFER_H_
20 |
21 | #include
22 |
23 | uint16_t to_float16(float x);
24 |
25 | void buffer_append_int16(uint8_t *buffer, int16_t number, int32_t *index);
26 | void buffer_append_uint16(uint8_t *buffer, uint16_t number, int32_t *index);
27 | void buffer_append_int32(uint8_t *buffer, int32_t number, int32_t *index);
28 | void buffer_append_uint32(uint8_t *buffer, uint32_t number, int32_t *index);
29 | void buffer_append_float16(uint8_t *buffer, float number, float scale, int32_t *index);
30 | void buffer_append_float32(uint8_t *buffer, float number, float scale, int32_t *index);
31 | void buffer_append_float32_auto(uint8_t *buffer, float number, int32_t *index);
32 | void buffer_append_float16_auto(uint8_t *buffer, float number, int32_t *index);
33 | void buffer_append_string(uint8_t *buffer, const char *str, int32_t *index);
34 | void buffer_append_string_max(uint8_t *buffer, const char *str, int32_t *index, uint8_t length);
35 | void buffer_append_string_fixed(uint8_t *buffer, const char *str, int32_t *index, uint8_t length);
36 |
37 | int16_t buffer_get_int16(const uint8_t *buffer, int32_t *index);
38 | uint16_t buffer_get_uint16(const uint8_t *buffer, int32_t *index);
39 | int32_t buffer_get_int32(const uint8_t *buffer, int32_t *index);
40 | uint32_t buffer_get_uint32(const uint8_t *buffer, int32_t *index);
41 | float buffer_get_float16(const uint8_t *buffer, float scale, int32_t *index);
42 | float buffer_get_float32(const uint8_t *buffer, float scale, int32_t *index);
43 | float buffer_get_float32_auto(const uint8_t *buffer, int32_t *index);
44 |
45 | #endif /* BUFFER_H_ */
46 |
--------------------------------------------------------------------------------
/vesc_pkg_lib/examples/speed_test/code.c:
--------------------------------------------------------------------------------
1 | /*
2 | Copyright 2022 Benjamin Vedder benjamin@vedder.se
3 |
4 | This file is part of the VESC firmware.
5 |
6 | The VESC firmware is free software: you can redistribute it and/or modify
7 | it under the terms of the GNU General Public License as published by
8 | the Free Software Foundation, either version 3 of the License, or
9 | (at your option) any later version.
10 |
11 | The VESC firmware is distributed in the hope that it will be useful,
12 | but WITHOUT ANY WARRANTY; without even the implied warranty of
13 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14 | GNU General Public License for more details.
15 |
16 | You should have received a copy of the GNU General Public License
17 | along with this program. If not, see .
18 | */
19 |
20 | #include "vesc_c_if.h"
21 |
22 | HEADER
23 |
24 | static int dec_cnt(volatile int x) {
25 | if (x == 0) {
26 | return 0;
27 | } else {
28 | return dec_cnt(x - 1);
29 | }
30 | }
31 |
32 | static lbm_value ext_dec_cnt(lbm_value *args, lbm_uint argn) {
33 | if (argn != 1 || !VESC_IF->lbm_is_number(args[0])) {
34 | return VESC_IF->lbm_enc_sym_eerror;
35 | }
36 |
37 | float t0 = VESC_IF->system_time();
38 | dec_cnt(VESC_IF->lbm_dec_as_i32(args[0]));
39 | float t1 = VESC_IF->system_time();
40 |
41 | return VESC_IF->lbm_enc_float(t1 - t0);
42 | }
43 |
44 | static int tak(volatile int x, volatile int y, volatile int z) {
45 | if (y >= x) {
46 | return z;
47 | } else {
48 | return tak(
49 | tak(x - 1, y, z),
50 | tak(y - 1, z, x),
51 | tak(z - 1, x, y));
52 | }
53 | }
54 |
55 | static lbm_value ext_tak(lbm_value *args, lbm_uint argn) {
56 | if (argn != 3 ||
57 | !VESC_IF->lbm_is_number(args[0]) ||
58 | !VESC_IF->lbm_is_number(args[1]) ||
59 | !VESC_IF->lbm_is_number(args[2])) {
60 | return VESC_IF->lbm_enc_sym_eerror;
61 | }
62 |
63 | float t0 = VESC_IF->system_time();
64 | int res = tak(VESC_IF->lbm_dec_as_i32(args[0]),
65 | VESC_IF->lbm_dec_as_i32(args[1]),
66 | VESC_IF->lbm_dec_as_i32(args[2]));
67 | float t1 = VESC_IF->system_time();
68 |
69 | VESC_IF->printf("C TakRes: %d", res);
70 |
71 | return VESC_IF->lbm_enc_float(t1 - t0);
72 | }
73 |
74 | INIT_FUN(lib_info *info) {
75 | INIT_START
76 |
77 | (void)info;
78 | VESC_IF->lbm_add_extension("ext-dec-cnt", ext_dec_cnt);
79 | VESC_IF->lbm_add_extension("ext-tak", ext_tak);
80 | return true;
81 | }
82 |
83 |
--------------------------------------------------------------------------------
/doc/commands/ALERTS_LIST.md:
--------------------------------------------------------------------------------
1 | # Command: ALERTS_LIST
2 |
3 | **ID**: 35
4 |
5 | **Status**: **unstable**
6 |
7 | Returns a list of active alerts and a log of alert history. The package maintains a number of last occurred alerts in a circular buffer. This command can return all of them, or, optionally provide a starting timestamp in ticks in the `since` argument. In such case only alerts which occurred after the timestamp are returned (note: the caller needs to take into account the possibility of the ticks overflowing, which occurs once every ~5 days).
8 |
9 | The response is limited to 511B in size, in case the alerts wouldn't fit in the message, the alert list will be trucncated (hence it's recommended to use the `since` argument to deal with this eventuality).
10 |
11 | ## Request
12 |
13 | | Offset | Size | Name | Mandatory | Description |
14 | |--------|------|---------|-----------|---------------|
15 | | 0 | 4 | `since` | No | Timestamp in ticks from which to list alerts in the log as `uint32`. |
16 |
17 | ## Response
18 |
19 | | Offset | Size | Name | Description |
20 | |--------|------|-----------------------|---------------|
21 | | 0 | 4 | `active_alert_mask_1` | Bits 0..31 of the `active_alert_mask`, indicating which [alert_id](alert_id.md)s are active. |
22 | | 4 | 8 | `active_alert_mask_2` | Bits 32..63 of the `active_alert_mask`, indicating which [alert_id](alert_id.md)s are active. |
23 | | 8 | 1 | `firmware_fault_code` | In case `ALERT_FW_FAULT` is active, the VESC firmware fault code, otherwise 0. |
24 | | 9 | ? | `firmware_fault_name` | Iff `firmware_fault_code` is non-zero, a [string](string.md) containing the firmware fault name.
25 | | ? | ? | `alert_log` | A sequence of `alert_record`s containing the alert history stored in the package. |
26 |
27 | **`alert_record`**:
28 | | Offset | Size | Name | Description |
29 | |--------|------|----------|---------------|
30 | | 0 | 4 | `time` | Timestamp of the alert in ticks, as `uint32`. |
31 | | 4 | 1 | `id` | The ID of the alert, see [alert_id](alert_id.md). |
32 | | 5 | 1 | `active` | `1` if the event represents the alert becoming active, `0` if the event marks the end of the alert. |
33 | | 6 | 1 | `code` | If the Alert ID is `ALERT_FW_FAULT`, the code of the fault from the firmware, otherwise 0. |
34 | | 7 | ? | `firmware_fault_name` | Iff Alert ID is `ALERT_FW_FAULT` and `firmware_fault_code` is non-zero, a [string](string.md) containing the firmware fault name.
35 |
--------------------------------------------------------------------------------
/src/footpad_sensor.c:
--------------------------------------------------------------------------------
1 | // Copyright 2024 Lukas Hrazky
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #include "footpad_sensor.h"
19 |
20 | #include "vesc_c_if.h"
21 |
22 | void footpad_sensor_init(FootpadSensor *fs) {
23 | fs->adc1 = 0.0f;
24 | fs->adc2 = 0.0f;
25 | fs->state = FS_NONE;
26 | }
27 |
28 | void footpad_sensor_update(FootpadSensor *fs, const RefloatConfig *config) {
29 | fs->adc1 = VESC_IF->io_read_analog(VESC_PIN_ADC1);
30 | // Returns -1.0 if the pin is missing on the hardware
31 | fs->adc2 = VESC_IF->io_read_analog(VESC_PIN_ADC2);
32 | if (fs->adc2 < 0.0) {
33 | fs->adc2 = 0.0;
34 | }
35 |
36 | fs->state = FS_NONE;
37 |
38 | if (config->fault_adc1 == 0 && config->fault_adc2 == 0) { // No sensors
39 | fs->state = FS_BOTH;
40 | } else if (config->fault_adc2 == 0) { // Single sensor on ADC1
41 | if (fs->adc1 > config->fault_adc1) {
42 | fs->state = FS_BOTH;
43 | }
44 | } else if (config->fault_adc1 == 0) { // Single sensor on ADC2
45 | if (fs->adc2 > config->fault_adc2) {
46 | fs->state = FS_BOTH;
47 | }
48 | } else { // Double sensor
49 | if (fs->adc1 > config->fault_adc1) {
50 | if (fs->adc2 > config->fault_adc2) {
51 | fs->state = FS_BOTH;
52 | } else {
53 | fs->state = FS_LEFT;
54 | }
55 | } else {
56 | if (fs->adc2 > config->fault_adc2) {
57 | fs->state = FS_RIGHT;
58 | }
59 | }
60 | }
61 | }
62 |
63 | int footpad_sensor_state_to_switch_compat(FootpadSensorState v) {
64 | switch (v) {
65 | case FS_BOTH:
66 | return 2;
67 | case FS_LEFT:
68 | case FS_RIGHT:
69 | return 1;
70 | case FS_NONE:
71 | default:
72 | return 0;
73 | }
74 | }
75 |
--------------------------------------------------------------------------------
/src/lib/circular_buffer.h:
--------------------------------------------------------------------------------
1 | // Copyright 2025 Lukas Hrazky
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #pragma once
19 |
20 | #include
21 | #include
22 | #include
23 |
24 | // Note: The circular buffer is not synchronized. Provide your own locking, or
25 | // at least insure it's only being written from a single thread and know that
26 | // data may not be consistent on reading.
27 |
28 | typedef struct {
29 | uint8_t *buffer;
30 | size_t length;
31 | size_t item_size;
32 | size_t head;
33 | size_t tail;
34 | bool empty;
35 | } CircularBuffer;
36 |
37 | void circular_buffer_init(CircularBuffer *cb, size_t item_size, size_t item_number, void *buffer);
38 |
39 | void circular_buffer_clear(CircularBuffer *cb);
40 |
41 | size_t circular_buffer_size(const CircularBuffer *cb);
42 |
43 | /**
44 | * Pushes an item into the buffer. In case it's full, replaces the last item.
45 | */
46 | void circular_buffer_push(CircularBuffer *cb, const void *item);
47 |
48 | /**
49 | * Gets an item at index i (a position relative to the current tail) from the
50 | * buffer without removing it. If there's no item at that index, leaves item
51 | * unchanged and returns false, otherwise returns true.
52 | */
53 | bool circular_buffer_get(const CircularBuffer *cb, size_t i, void *item);
54 |
55 | /**
56 | * Pops an item at index i (a position relative to the current tail) from the
57 | * buffer. If there's no item at that index, leaves item unchanged and returns
58 | * false, otherwise returns true.
59 | */
60 | bool circular_buffer_pop(CircularBuffer *cb, size_t i, void *item);
61 |
62 | /**
63 | * Iterates over the buffer, calling the callback function on each item.
64 | */
65 | void circular_buffer_iterate(
66 | const CircularBuffer *cb, void (*callback)(const void *item, void *data), void *data
67 | );
68 |
--------------------------------------------------------------------------------
/src/state.h:
--------------------------------------------------------------------------------
1 | // Copyright 2024 Lukas Hrazky
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #pragma once
19 |
20 | #include
21 | #include
22 |
23 | typedef enum {
24 | STATE_DISABLED = 0,
25 | STATE_STARTUP = 1,
26 | STATE_READY = 2,
27 | STATE_RUNNING = 3
28 | } RunState;
29 |
30 | typedef enum {
31 | MODE_NORMAL = 0,
32 | MODE_HANDTEST = 1,
33 | MODE_FLYWHEEL = 2
34 | } Mode;
35 |
36 | typedef enum {
37 | STOP_NONE = 0,
38 | STOP_PITCH = 1,
39 | STOP_ROLL = 2,
40 | STOP_SWITCH_HALF = 3,
41 | STOP_SWITCH_FULL = 4,
42 | STOP_REVERSE_STOP = 5,
43 | STOP_QUICKSTOP = 6
44 | } StopCondition;
45 |
46 | // leaving gaps for more states inbetween the different "classes" of the types
47 | // (normal / warning / error)
48 | typedef enum {
49 | SAT_NONE = 0,
50 | SAT_CENTERING = 1,
51 | SAT_REVERSESTOP = 2,
52 | SAT_PB_SPEED = 5,
53 | SAT_PB_DUTY = 6,
54 | SAT_PB_ERROR = 7,
55 | SAT_PB_HIGH_VOLTAGE = 10,
56 | SAT_PB_LOW_VOLTAGE = 11,
57 | SAT_PB_TEMPERATURE = 12
58 | } SetpointAdjustmentType;
59 |
60 | typedef struct {
61 | RunState state;
62 | Mode mode;
63 | SetpointAdjustmentType sat;
64 | StopCondition stop_condition;
65 | bool charging;
66 | bool wheelslip;
67 | bool darkride;
68 | } State;
69 |
70 | void state_init(State *state);
71 |
72 | void state_stop(State *state, StopCondition stop_condition);
73 |
74 | void state_engage(State *state);
75 |
76 | void state_set_disabled(State *state, bool disabled);
77 |
78 | /**
79 | * Compatibility function for the Float State enum for the app data commands.
80 | */
81 | uint8_t state_compat(const State *state);
82 |
83 | /**
84 | * Compatibility function for the Float SetpointAdjustmentType enum for the app
85 | * data commands.
86 | */
87 | uint8_t sat_compat(const State *state);
88 |
--------------------------------------------------------------------------------
/src/imu.c:
--------------------------------------------------------------------------------
1 | // Copyright 2025 Lukas Hrazky
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #include "imu.h"
19 |
20 | #include "utils.h"
21 |
22 | #include "vesc_c_if.h"
23 |
24 | void imu_init(IMU *imu) {
25 | imu->pitch = 0.0f;
26 | imu->balance_pitch = 0.0f;
27 | imu->roll = 0.0f;
28 | imu->yaw = 0.0f;
29 | imu->pitch_rate = 0.0f;
30 |
31 | imu->flywheel_pitch_offset = 0.0f;
32 | imu->flywheel_roll_offset = 0.0f;
33 | }
34 |
35 | void imu_update(IMU *imu, const BalanceFilterData *bf, const State *state) {
36 | float roll_rad = VESC_IF->imu_get_roll(); // in Radians
37 |
38 | imu->pitch = rad2deg(VESC_IF->imu_get_pitch());
39 | imu->roll = rad2deg(roll_rad);
40 | imu->yaw = rad2deg(VESC_IF->imu_get_yaw());
41 | imu->balance_pitch = rad2deg(balance_filter_get_pitch(bf));
42 |
43 | float gyro[3];
44 | VESC_IF->imu_get_gyro(gyro);
45 |
46 | float sin_roll = sinf(roll_rad);
47 | float cos_roll = cosf(roll_rad);
48 |
49 | // Rotated to diminish influence of Yaw Change on Gyro Y when board is rolled
50 | // (Estimates Pitch Rate solely due to rider input, without influence from board turning)
51 | imu->pitch_rate = cos_roll * cos_roll * gyro[1] + sin_roll * cos_roll * gyro[2];
52 | if (state->darkride) {
53 | imu->pitch_rate = -imu->pitch_rate;
54 | }
55 |
56 | if (state->mode == MODE_FLYWHEEL) {
57 | imu->pitch = imu->flywheel_pitch_offset - imu->pitch;
58 | imu->balance_pitch = imu->pitch;
59 | imu->roll -= imu->flywheel_roll_offset;
60 | if (imu->roll < -200) {
61 | imu->roll += 360;
62 | } else if (imu->roll > 200) {
63 | imu->roll -= 360;
64 | }
65 | }
66 | }
67 |
68 | void imu_set_flywheel_offsets(IMU *imu) {
69 | imu->flywheel_pitch_offset = imu->pitch;
70 | imu->flywheel_roll_offset = imu->roll;
71 | }
72 |
--------------------------------------------------------------------------------
/src/motor_data.h:
--------------------------------------------------------------------------------
1 | // Copyright 2024 Lukas Hrazky
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #pragma once
19 |
20 | #include "alert_tracker.h"
21 | #include "biquad.h"
22 |
23 | #include
24 | #include
25 |
26 | #define ACCEL_ARRAY_SIZE 40
27 |
28 | typedef struct {
29 | float erpm;
30 | float abs_erpm;
31 | float abs_erpm_smooth;
32 | float last_erpm;
33 | int8_t erpm_sign;
34 |
35 | float speed;
36 |
37 | float current; // "regular" motor current (positive = accelerating, negative = braking)
38 | float dir_current; // directional current (sign represents direction of torque generation)
39 | float filt_current; // filtered directional current
40 | bool braking;
41 |
42 | float duty_cycle;
43 | float duty_raw;
44 |
45 | // an average calculated over last ACCEL_ARRAY_SIZE values
46 | float acceleration;
47 |
48 | float batt_current;
49 | float batt_voltage;
50 |
51 | float mosfet_temp;
52 | float motor_temp;
53 |
54 | // The following values are periodically updated from the aux thread
55 | float current_min;
56 | float current_max;
57 | float battery_current_min;
58 | float battery_current_max;
59 | float mosfet_temp_max;
60 | float motor_temp_max;
61 | float duty_max_with_margin;
62 | float lv_threshold;
63 | float hv_threshold;
64 |
65 | float accel_history[ACCEL_ARRAY_SIZE];
66 | uint8_t accel_idx;
67 |
68 | bool current_filter_enabled;
69 | Biquad current_biquad;
70 | } MotorData;
71 |
72 | void motor_data_init(MotorData *m);
73 |
74 | void motor_data_reset(MotorData *m);
75 |
76 | void motor_data_refresh_motor_config(MotorData *m, float lv_threshold, float hv_threshold);
77 |
78 | void motor_data_configure(MotorData *m, float frequency);
79 |
80 | void motor_data_update(MotorData *m);
81 |
82 | void motor_data_evaluate_alerts(const MotorData *m, AlertTracker *at, const Time *time);
83 |
84 | float motor_data_get_current_saturation(const MotorData *m);
85 |
--------------------------------------------------------------------------------
/src/leds.h:
--------------------------------------------------------------------------------
1 | // Copyright 2024 Lukas Hrazky
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #pragma once
19 |
20 | #include "conf/datatypes.h"
21 | #include "footpad_sensor.h"
22 | #include "led_driver.h"
23 | #include "led_strip.h"
24 | #include "state.h"
25 |
26 | #define LEDS_REFRESH_RATE 30
27 |
28 | typedef struct {
29 | LedTransition transition;
30 | float split;
31 | } TransitionState;
32 |
33 | typedef struct {
34 | LedStrip status_strip;
35 | LedStrip front_strip;
36 | LedStrip rear_strip;
37 |
38 | const CfgLeds *cfg;
39 |
40 | float last_updated;
41 | State state;
42 | float pitch;
43 |
44 | float left_sensor;
45 | float right_sensor;
46 |
47 | float on_off_fade;
48 |
49 | float duty_threshold;
50 | float status_duty_blend;
51 | float status_idle_blend;
52 | float status_idle_time;
53 | float status_animation_start;
54 |
55 | float status_on_front_blend;
56 | float status_on_front_idle_blend;
57 | float status_on_front_idle_time;
58 | bool board_is_upright;
59 |
60 | float split_distance;
61 | bool headlights_on;
62 | bool direction_forward;
63 | float headlights_time;
64 | float animation_start;
65 |
66 | float confirm_animation_start;
67 |
68 | TransitionState headlights_trans;
69 | TransitionState dir_trans;
70 |
71 | const LedBar *front_bar;
72 | const LedBar *front_dir_target;
73 | const LedBar *front_time_target;
74 |
75 | const LedBar *rear_bar;
76 | const LedBar *rear_dir_target;
77 | const LedBar *rear_time_target;
78 |
79 | uint32_t *led_data;
80 | LedDriver led_driver;
81 | } Leds;
82 |
83 | void leds_init(Leds *leds);
84 |
85 | void leds_setup(Leds *leds, CfgHwLeds *hw_cfg, const CfgLeds *cfg, FootpadSensorState fs_state);
86 |
87 | void leds_configure(Leds *leds, const CfgLeds *cfg);
88 |
89 | void leds_update(Leds *leds, const State *state, FootpadSensorState fs_state);
90 |
91 | void leds_status_confirm(Leds *leds);
92 |
93 | void leds_destroy(Leds *leds);
94 |
--------------------------------------------------------------------------------
/src/booster.c:
--------------------------------------------------------------------------------
1 | // Copyright 2024 Lukas Hrazky
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #include "booster.h"
19 |
20 | #include "utils.h"
21 |
22 | #include
23 |
24 | void booster_init(Booster *b) {
25 | booster_reset(b);
26 | }
27 |
28 | void booster_reset(Booster *b) {
29 | b->current = 0.0f;
30 | }
31 |
32 | void booster_update(
33 | Booster *b, const MotorData *md, const RefloatConfig *config, float proportional
34 | ) {
35 | float current;
36 | float angle;
37 | float ramp;
38 | if (md->braking) {
39 | current = config->brkbooster_current;
40 | angle = config->brkbooster_angle;
41 | ramp = config->brkbooster_ramp;
42 | } else {
43 | current = config->booster_current;
44 | angle = config->booster_angle;
45 | ramp = config->booster_ramp;
46 | }
47 |
48 | // Make booster a bit stronger at higher speed (up to 2x stronger when braking)
49 | const int boost_min_erpm = 3000;
50 | if (md->abs_erpm > boost_min_erpm) {
51 | float speedstiffness = fminf(1, (md->abs_erpm - boost_min_erpm) / 10000);
52 | if (md->braking) {
53 | // use higher current at speed when braking
54 | current += current * speedstiffness;
55 | } else {
56 | // when accelerating, we reduce the booster start angle as we get faster
57 | // strength remains unchanged
58 | float angledivider = 1 + speedstiffness;
59 | angle /= angledivider;
60 | }
61 | }
62 |
63 | float abs_proportional = fabsf(proportional);
64 | if (abs_proportional > angle) {
65 | if (abs_proportional - angle < ramp) {
66 | current *= sign(proportional) * (abs_proportional - angle) / ramp;
67 | } else {
68 | current *= sign(proportional);
69 | }
70 | } else {
71 | current = 0;
72 | }
73 |
74 | // No harsh changes in booster current (effective delay <= 100ms)
75 | b->current = 0.01 * current + 0.99 * b->current;
76 | }
77 |
--------------------------------------------------------------------------------
/vesc_pkg_lib/examples/ssd1306/code.c:
--------------------------------------------------------------------------------
1 | /*
2 | Copyright 2022 Benjamin Vedder benjamin@vedder.se
3 |
4 | This file is part of the VESC firmware.
5 |
6 | The VESC firmware is free software: you can redistribute it and/or modify
7 | it under the terms of the GNU General Public License as published by
8 | the Free Software Foundation, either version 3 of the License, or
9 | (at your option) any later version.
10 |
11 | The VESC firmware is distributed in the hope that it will be useful,
12 | but WITHOUT ANY WARRANTY; without even the implied warranty of
13 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14 | GNU General Public License for more details.
15 |
16 | You should have received a copy of the GNU General Public License
17 | along with this program. If not, see .
18 | */
19 |
20 | #include "vesc_c_if.h"
21 |
22 | HEADER
23 |
24 | static int abs(int x) {
25 | if (x >= 0) {
26 | return x;
27 | } else {
28 | return -x;
29 | }
30 | }
31 |
32 | static void set_pix(uint8_t *arr, int x, int y) {
33 | if (x < 0 || x >= 128 || y < 0 || y >= 64) {
34 | return;
35 | }
36 | unsigned int pos = 8 + x * 8 + y % 8 + (y / 8) * 1024;
37 | unsigned int bytepos = pos / 8;
38 | unsigned int bitpos = pos % 8;
39 | arr[bytepos] |= (1 << bitpos);
40 | }
41 |
42 | static void draw_line(uint8_t *arr, int x0, int y0, int x1, int y1) {
43 | int dx = abs(x1 - x0);
44 | int sx = x0 < x1 ? 1 : -1;
45 | int dy = -abs(y1 - y0);
46 | int sy = y0 < y1 ? 1 : -1;
47 | int error = dx + dy;
48 |
49 | while (true) {
50 | set_pix(arr, x0, y0);
51 | if (x0 == x1 && y0 == y1) {
52 | break;
53 | }
54 | if ((error * 2) >= dy) {
55 | if (x0 == x1) {
56 | break;
57 | }
58 | error += dy;
59 | x0 += sx;
60 | }
61 | if ((error * 2) <= dx) {
62 | if (y0 == y1) {
63 | break;
64 | }
65 | error += dx;
66 | y0 += sy;
67 | }
68 | }
69 | }
70 |
71 | static lbm_value ssd_drawline(lbm_value *args, lbm_uint argn) {
72 | lbm_value res = VESC_IF->lbm_enc_sym_eerror;
73 |
74 | if (argn != 5 || !VESC_IF->lbm_is_byte_array(args[0]) ||
75 | !VESC_IF->lbm_is_number(args[1]) || !VESC_IF->lbm_is_number(args[2]) ||
76 | !VESC_IF->lbm_is_number(args[3]) || !VESC_IF->lbm_is_number(args[4])) {
77 | return res;
78 | }
79 |
80 | uint8_t *pixbuf = (uint8_t*)VESC_IF->lbm_dec_str(args[0]);
81 | int x0 = VESC_IF->lbm_dec_as_i32(args[1]);
82 | int y0 = VESC_IF->lbm_dec_as_i32(args[2]);
83 | int x1 = VESC_IF->lbm_dec_as_i32(args[3]);
84 | int y1 = VESC_IF->lbm_dec_as_i32(args[4]);
85 |
86 | draw_line(pixbuf, x0, y0, x1, y1);
87 |
88 | return VESC_IF->lbm_enc_sym_true;
89 | }
90 |
91 | INIT_FUN(lib_info *info) {
92 | INIT_START
93 |
94 | (void)info;
95 | VESC_IF->lbm_add_extension("ext-drawline", ssd_drawline);
96 | return true;
97 | }
98 |
99 |
--------------------------------------------------------------------------------
/src/utils.c:
--------------------------------------------------------------------------------
1 | // Copyright 2024 Lukas Hrazky
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #include "utils.h"
19 |
20 | #include
21 |
22 | uint32_t rnd(uint32_t seed) {
23 | return seed * 1664525u + 1013904223u;
24 | }
25 |
26 | void rate_limitf(float *value, float target, float step) {
27 | if (fabsf(target - *value) < step) {
28 | *value = target;
29 | } else if (target - *value > 0) {
30 | *value += step;
31 | } else {
32 | *value -= step;
33 | }
34 | }
35 |
36 | // Smoothen changes in tilt angle by ramping the step size
37 | // smooth_center_window: Sets the angle away from Target that step size begins ramping down
38 | void smooth_rampf(
39 | float *value,
40 | float *ramped_step,
41 | float target,
42 | float step,
43 | float smoothing_factor,
44 | float smooth_center_window
45 | ) {
46 | float tiltback_target_diff = target - *value;
47 |
48 | // Within X degrees of Target Angle, start ramping down step size
49 | if (fabsf(tiltback_target_diff) < smooth_center_window) {
50 | // Target step size is reduced the closer to center you are (needed for smoothly
51 | // transitioning away from center)
52 | *ramped_step = (smoothing_factor * step * (tiltback_target_diff / 2)) +
53 | ((1 - smoothing_factor) * *ramped_step);
54 | // Linearly ramped down step size is provided as minimum to prevent overshoot
55 | float centering_step = fminf(fabsf(*ramped_step), fabsf(tiltback_target_diff / 2) * step) *
56 | sign(tiltback_target_diff);
57 | if (fabsf(tiltback_target_diff) < fabsf(centering_step)) {
58 | *value = target;
59 | } else {
60 | *value += centering_step;
61 | }
62 | } else {
63 | // Ramp up step size until the configured tilt speed is reached
64 | *ramped_step = (smoothing_factor * step * sign(tiltback_target_diff)) +
65 | ((1 - smoothing_factor) * *ramped_step);
66 | *value += *ramped_step;
67 | }
68 | }
69 |
70 | float clampf(float value, float min, float max) {
71 | const float m = value < min ? min : value;
72 | return m > max ? max : m;
73 | }
74 |
--------------------------------------------------------------------------------
/.github/workflows/create_release.yml:
--------------------------------------------------------------------------------
1 | name: Create Release
2 |
3 | on:
4 | push:
5 | tags:
6 | - 'v[0-9]+.[0-9]+.[0-9]+'
7 | - 'v[0-9]+.[0-9]+.[0-9]+-beta[0-9]+'
8 | - '*-preview[0-9]+'
9 |
10 | jobs:
11 | create_release:
12 | name: Create Release
13 | permissions:
14 | contents: write
15 | runs-on: ubuntu-24.04
16 | steps:
17 | - uses: actions/checkout@v4
18 | with:
19 | fetch-depth: 0
20 |
21 | - name: Extract Version
22 | run: |
23 | TAG="${{github.ref_name}}"
24 | if [[ $TAG =~ ^v[0-9]+\.[0-9]+\.[0-9]+ ]]; then
25 | echo "VERSION=${TAG#v}" >> $GITHUB_ENV
26 | else
27 | echo "VERSION=${TAG}" >> $GITHUB_ENV
28 | fi
29 | if [[ $TAG =~ ^v[0-9]+\.[0-9]+\.[0-9]+$ ]]; then
30 | echo "PRERELEASE=false" >> $GITHUB_ENV
31 | else
32 | echo "PRERELEASE=true" >> $GITHUB_ENV
33 | fi
34 | if [[ $TAG =~ -preview[0-9]+$ ]]; then
35 | echo "PREVIEW=true" >> $GITHUB_ENV
36 | else
37 | echo "PREVIEW=false" >> $GITHUB_ENV
38 | fi
39 |
40 |
41 | - name: Check Tag Matches Version
42 | run: |
43 | VER="`cat version`"
44 | if [ "${{env.VERSION}}" != "$VER" ]; then
45 | echo "Error: Tag version (${{env.VERSION}}) doesn't match version file ($VER)."
46 | exit 1
47 | fi
48 |
49 | - name: Build Package
50 | uses: ./.github/actions/build
51 | with:
52 | cache-auth-token: '${{ secrets.CACHIX_AUTH_TOKEN }}'
53 |
54 | - name: Extract Config Signature
55 | run: cat src/conf/confparser.h | sed -n 's/^#define .\+_SIGNATURE\W\+\([0-9]*\)/\1/p' > config_signature.txt
56 |
57 | - name: Rename Package File
58 | run: |
59 | mv refloat.vescpkg refloat-${{env.VERSION}}.vescpkg
60 | mv src/package_lib.elf refloat-${{env.VERSION}}.elf
61 |
62 | - name: Install Changelog Generation Dependencies
63 | run: sudo apt-get install python3-git
64 |
65 | - name: Generate Release Notes
66 | run: |
67 | if [[ "${{env.PREVIEW}}" == "true" ]]; then
68 | echo "**WARNING: This is an experimental version of the package. Bugs may and will be present. Be very careful!**" > release_notes.md
69 | echo "" >> release_notes.md
70 | fi
71 | python changelog.py >> release_notes.md
72 |
73 | - name: Create Release
74 | uses: ncipollo/release-action@v1
75 | with:
76 | tag: ${{github.ref}}
77 | name: Refloat ${{env.VERSION}}
78 | draft: true
79 | artifacts: "refloat-${{env.VERSION}}.vescpkg,refloat-${{env.VERSION}}.elf,config_signature.txt"
80 | bodyFile: "release_notes.md"
81 | prerelease: ${{env.PRERELEASE}}
82 | allowUpdates: true
83 |
--------------------------------------------------------------------------------
/vesc_pkg_lib/examples/custom_data_comm/code.c:
--------------------------------------------------------------------------------
1 | /*
2 | Copyright 2022 Benjamin Vedder benjamin@vedder.se
3 |
4 | This file is part of the VESC firmware.
5 |
6 | The VESC firmware is free software: you can redistribute it and/or modify
7 | it under the terms of the GNU General Public License as published by
8 | the Free Software Foundation, either version 3 of the License, or
9 | (at your option) any later version.
10 |
11 | The VESC firmware is distributed in the hope that it will be useful,
12 | but WITHOUT ANY WARRANTY; without even the implied warranty of
13 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14 | GNU General Public License for more details.
15 |
16 | You should have received a copy of the GNU General Public License
17 | along with this program. If not, see .
18 | */
19 |
20 | #include "vesc_c_if.h"
21 | #include "buffer.h"
22 |
23 | HEADER
24 |
25 | typedef struct {
26 | int msg_cnt;
27 | float msg_val;
28 | lib_thread thread;
29 | } my_data;
30 |
31 | // This thread sends the message counter and the last received data
32 | // back every second. The Commands-signal onCustomAppDataReceived
33 | // is received every time VESC_IF->send_app_data is used.
34 | static void thd(void *arg) {
35 | volatile my_data *d = (my_data*)arg;
36 |
37 | while (!VESC_IF->should_terminate()) {
38 | int32_t ind = 0;
39 | uint8_t buffer[10];
40 | buffer_append_int32(buffer, d->msg_cnt, &ind);
41 | buffer_append_float32_auto(buffer, d->msg_val, &ind);
42 | VESC_IF->send_app_data(buffer, ind);
43 | VESC_IF->sleep_ms(1000);
44 | }
45 | }
46 |
47 | // This callback is called every time mCommands.sendCustomAppData is used
48 | // with the data it sends. The VESC buffer functions are compatible with
49 | // the JavaScript DataView, so we can even communicate floats as in this
50 | // example. Here we decode and save the data and increase a message
51 | // counter.
52 | static void data_rx_cb(unsigned char *data, unsigned int len) {
53 | volatile my_data *d = (my_data*)ARG;
54 | int32_t ind = 0;
55 | d->msg_val = buffer_get_float32_auto(data, &ind);
56 | d->msg_cnt++;
57 | VESC_IF->printf("Received %d bytes, number %.2f", len, (double)d->msg_val);
58 | }
59 |
60 | // Called when code is stopped
61 | static void stop(void *arg) {
62 | my_data *d = (my_data*)arg;
63 | VESC_IF->request_terminate(d->thread);
64 | VESC_IF->set_app_data_handler(0); // Unregisted callback-function
65 | VESC_IF->printf("Terminated");
66 | VESC_IF->free(d);
67 | }
68 |
69 | INIT_FUN(lib_info *info) {
70 | INIT_START
71 |
72 | my_data *d = VESC_IF->malloc(sizeof(my_data));
73 | d->msg_val = 0.0;
74 | d->msg_cnt = 0.0;
75 | d->thread = VESC_IF->spawn(thd, 2048, "LibThd", d);
76 |
77 | info->stop_fun = stop;
78 | info->arg = d;
79 |
80 | // Register callback function that is used when app data is received
81 | VESC_IF->set_app_data_handler(data_rx_cb);
82 |
83 | return true;
84 | }
85 |
86 |
--------------------------------------------------------------------------------
/src/lcm.h:
--------------------------------------------------------------------------------
1 | // Copyright 2024 Lukas Hrazky
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #pragma once
19 |
20 | #include "footpad_sensor.h"
21 | #include "motor_data.h"
22 | #include "state.h"
23 |
24 | #include
25 |
26 | typedef enum {
27 | COMMAND_LCM_POLL = 24, // this should only be called by external light modules
28 | COMMAND_LCM_LIGHT_INFO = 25, // to be called by apps to get lighting info
29 | COMMAND_LCM_LIGHT_CTRL = 26, // to be called by apps to change light settings
30 | COMMAND_LCM_DEVICE_INFO = 27, // to be called by apps to check lighting controller firmware
31 | COMMAND_LCM_GET_BATTERY = 29,
32 |
33 | COMMAND_LCM_DEBUG = 99, // reserved for external debug purposes
34 | } LcmCommands;
35 |
36 | #define MAX_LCM_NAME_LENGTH 20
37 | #define MAX_LCM_PAYLOAD_LENGTH 64
38 |
39 | typedef struct {
40 | bool enabled;
41 | uint8_t brightness;
42 | uint8_t brightness_idle;
43 | uint8_t status_brightness;
44 | bool lights_off_when_lifted;
45 |
46 | char name[MAX_LCM_NAME_LENGTH];
47 | uint8_t payload[MAX_LCM_PAYLOAD_LENGTH];
48 | uint8_t payload_size;
49 | } LcmData;
50 |
51 | void lcm_init(LcmData *lcm, CfgHwLeds *hw_cfg);
52 |
53 | void lcm_configure(LcmData *lcm, const CfgLeds *cfg);
54 |
55 | /**
56 | * Poll request from LCM with any data that need to be passed to the package.
57 | */
58 | void lcm_poll_request(LcmData *lcm, uint8_t *buffer, size_t len);
59 |
60 | /**
61 | * Response to the LCM poll request to get data from the package.
62 | */
63 | void lcm_poll_response(
64 | LcmData *lcm,
65 | const State *state,
66 | FootpadSensorState fs_state,
67 | const MotorData *motor,
68 | const float pitch
69 | );
70 |
71 | /**
72 | * Command for apps to call to get info about lighting.
73 | */
74 | void lcm_light_info_response(const LcmData *lcm);
75 |
76 | /**
77 | * Command for apps to call to get LCM hardware info (if any).
78 | */
79 | void lcm_device_info_response(const LcmData *lcm);
80 |
81 | /**
82 | * No idea why this exists. Seems it should have been part of lcm_poll_response().
83 | */
84 | void lcm_get_battery_response(const LcmData *lcm);
85 |
86 | /**
87 | * Command for apps to call to control LCM details (lights, behavior, etc).
88 | */
89 | void lcm_light_ctrl_request(LcmData *lcm, unsigned char *cfg, int len);
90 |
--------------------------------------------------------------------------------
/src/bms.c:
--------------------------------------------------------------------------------
1 | // Copyright 2024 Syler Clayton
2 | // Copyright 2025 Lukas Hrazky
3 | //
4 | // This file is part of the Refloat VESC package.
5 | //
6 | // Refloat VESC package is free software: you can redistribute it and/or modify
7 | // it under the terms of the GNU General Public License as published by the
8 | // Free Software Foundation, either version 3 of the License, or (at your
9 | // option) any later version.
10 | //
11 | // Refloat VESC package is distributed in the hope that it will be useful, but
12 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
13 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
14 | // more details.
15 | //
16 | // You should have received a copy of the GNU General Public License along with
17 | // this program. If not, see .
18 |
19 | #include "bms.h"
20 |
21 | #include
22 |
23 | void bms_init(BMS *bms) {
24 | bms->cell_lv = 0.0f;
25 | bms->cell_hv = 0.0f;
26 | bms->cell_lt = 0;
27 | bms->cell_ht = 0;
28 | bms->bms_ht = 0;
29 | bms->msg_age = 42.0f;
30 | bms->fault_mask = BMSF_NONE;
31 | }
32 |
33 | static inline void set_fault(uint32_t *fault_mask, BMSFaultCode fault_code) {
34 | *fault_mask |= 1u << (fault_code - 1);
35 | }
36 |
37 | void bms_update(BMS *bms, const CfgBMS *cfg, const Time *time) {
38 | if (!cfg->enabled) {
39 | bms->fault_mask = BMSF_NONE;
40 | return;
41 | }
42 |
43 | uint32_t fault_mask = BMSF_NONE;
44 | const float timeout = 5.0f;
45 |
46 | // Before the first BMS update occurs right after startup, msg_age has its
47 | // init value. We need to wait the `timeout` time before issuing errors.
48 | if (bms->msg_age > timeout && time_elapsed(time, start, timeout)) {
49 | set_fault(&fault_mask, BMSF_CONNECTION);
50 | bms->fault_mask = fault_mask;
51 | return;
52 | }
53 |
54 | if (bms->cell_lv < cfg->cell_lv_threshold) {
55 | set_fault(&fault_mask, BMSF_CELL_UNDER_VOLTAGE);
56 | }
57 |
58 | if (bms->cell_hv > cfg->cell_hv_threshold) {
59 | set_fault(&fault_mask, BMSF_CELL_OVER_VOLTAGE);
60 | }
61 |
62 | // Setting high temp threshold to 0 disables both high and low temp checking
63 | if (cfg->cell_ht_threshold > 0) {
64 | if (bms->cell_ht > cfg->cell_ht_threshold) {
65 | set_fault(&fault_mask, BMSF_CELL_OVER_TEMP);
66 | }
67 |
68 | if (bms->cell_lt < cfg->cell_lt_threshold) {
69 | set_fault(&fault_mask, BMSF_CELL_UNDER_TEMP);
70 | }
71 | }
72 |
73 | if (cfg->bms_ht_threshold > 0 && bms->bms_ht > cfg->bms_ht_threshold) {
74 | set_fault(&fault_mask, BMSF_OVER_TEMP);
75 | }
76 |
77 | if (fabsf(bms->cell_lv - bms->cell_hv) > cfg->cell_balance_threshold) {
78 | set_fault(&fault_mask, BMSF_CELL_BALANCE);
79 | }
80 |
81 | bms->fault_mask = fault_mask;
82 | }
83 |
84 | bool bms_is_fault(const BMS *bms, BMSFaultCode fault_code) {
85 | return (bms->fault_mask & (1u << (fault_code - 1))) != 0;
86 | }
87 |
--------------------------------------------------------------------------------
/src/pid.c:
--------------------------------------------------------------------------------
1 | // Copyright 2025 Lukas Hrazky
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #include "pid.h"
19 |
20 | #include "utils.h"
21 |
22 | #include "vesc_c_if.h"
23 |
24 | #include
25 |
26 | void pid_init(PID *pid) {
27 | pid->p = 0;
28 | pid->i = 0;
29 | pid->rate_p = 0;
30 |
31 | pid->kp_brake_scale = 1.0;
32 | pid->kp2_brake_scale = 1.0;
33 | pid->kp_accel_scale = 1.0;
34 | pid->kp2_accel_scale = 1.0;
35 | }
36 |
37 | void pid_update(
38 | PID *pid, float setpoint, const MotorData *md, const IMU *imu, const RefloatConfig *config
39 | ) {
40 | pid->p = setpoint - imu->balance_pitch;
41 | pid->i = pid->i + pid->p * config->ki;
42 |
43 | // I term filter
44 | if (config->ki_limit > 0 && fabsf(pid->i) > config->ki_limit) {
45 | pid->i = config->ki_limit * sign(pid->i);
46 | }
47 |
48 | // brake scale coefficient smoothing
49 | if (md->abs_erpm < 500) {
50 | // all scaling should roll back to 1.0 when near a stop for smooth transitions
51 | pid->kp_brake_scale = 0.01 + 0.99 * pid->kp_brake_scale;
52 | pid->kp2_brake_scale = 0.01 + 0.99 * pid->kp2_brake_scale;
53 | pid->kp_accel_scale = 0.01 + 0.99 * pid->kp_accel_scale;
54 | pid->kp2_accel_scale = 0.01 + 0.99 * pid->kp2_accel_scale;
55 | } else if (md->erpm > 0) {
56 | // rolling forward - brakes transition to scaled values
57 | pid->kp_brake_scale = 0.01 * config->kp_brake + 0.99 * pid->kp_brake_scale;
58 | pid->kp2_brake_scale = 0.01 * config->kp2_brake + 0.99 * pid->kp2_brake_scale;
59 | pid->kp_accel_scale = 0.01 + 0.99 * pid->kp_accel_scale;
60 | pid->kp2_accel_scale = 0.01 + 0.99 * pid->kp2_accel_scale;
61 | } else {
62 | // rolling backward, NEW brakes (we use kp_accel) transition to scaled values
63 | pid->kp_brake_scale = 0.01 + 0.99 * pid->kp_brake_scale;
64 | pid->kp2_brake_scale = 0.01 + 0.99 * pid->kp2_brake_scale;
65 | pid->kp_accel_scale = 0.01 * config->kp_brake + 0.99 * pid->kp_accel_scale;
66 | pid->kp2_accel_scale = 0.01 * config->kp2_brake + 0.99 * pid->kp2_accel_scale;
67 | }
68 |
69 | pid->p *= config->kp * (pid->p > 0 ? pid->kp_accel_scale : pid->kp_brake_scale);
70 |
71 | pid->rate_p = -imu->pitch_rate * config->kp2;
72 | pid->rate_p *= pid->rate_p > 0 ? pid->kp2_accel_scale : pid->kp2_brake_scale;
73 | }
74 |
--------------------------------------------------------------------------------
/src/torque_tilt.c:
--------------------------------------------------------------------------------
1 | // Copyright 2022 Dado Mista
2 | // Copyright 2024 Lukas Hrazky
3 | //
4 | // This file is part of the Refloat VESC package.
5 | //
6 | // Refloat VESC package is free software: you can redistribute it and/or modify
7 | // it under the terms of the GNU General Public License as published by the
8 | // Free Software Foundation, either version 3 of the License, or (at your
9 | // option) any later version.
10 | //
11 | // Refloat VESC package is distributed in the hope that it will be useful, but
12 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
13 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
14 | // more details.
15 | //
16 | // You should have received a copy of the GNU General Public License along with
17 | // this program. If not, see .
18 |
19 | #include "torque_tilt.h"
20 |
21 | #include "utils.h"
22 |
23 | #include
24 |
25 | void torque_tilt_init(TorqueTilt *tt) {
26 | tt->on_step_size = 0.0f;
27 | tt->off_step_size = 0.0f;
28 | torque_tilt_reset(tt);
29 | }
30 |
31 | void torque_tilt_reset(TorqueTilt *tt) {
32 | tt->ramped_step_size = 0.0f;
33 | tt->setpoint = 0.0f;
34 | }
35 |
36 | void torque_tilt_configure(TorqueTilt *tt, const RefloatConfig *config) {
37 | tt->on_step_size = config->torquetilt_on_speed / config->hertz;
38 | tt->off_step_size = config->torquetilt_off_speed / config->hertz;
39 | }
40 |
41 | void torque_tilt_update(TorqueTilt *tt, const MotorData *motor, const RefloatConfig *config) {
42 | float strength =
43 | motor->braking ? config->torquetilt_strength_regen : config->torquetilt_strength;
44 |
45 | // Take abs motor current, subtract start offset, and take the max of that
46 | // with 0 to get the current above our start threshold (absolute). Then
47 | // multiply it by "power" to get our desired angle, and min with the limit
48 | // to respect boundaries. Finally multiply it by motor current sign to get
49 | // directionality back.
50 | float target =
51 | fminf(
52 | fmaxf((fabsf(motor->filt_current) - config->torquetilt_start_current), 0) * strength,
53 | config->torquetilt_angle_limit
54 | ) *
55 | sign(motor->filt_current);
56 |
57 | float step_size = 0;
58 | if (tt->setpoint * target < 0) {
59 | // Moving towards opposite sign (crossing zero);
60 | // Use the faster tilt speed until 0 is reached
61 | step_size = fmaxf(tt->off_step_size, tt->on_step_size);
62 | } else if (fabsf(tt->setpoint) > fabsf(target)) {
63 | // Moving towards smaller angle of same sign or zero
64 | step_size = tt->off_step_size;
65 | } else {
66 | // Moving towards larger angle of same sign
67 | step_size = tt->on_step_size;
68 | }
69 |
70 | if (motor->abs_erpm < 500) {
71 | step_size /= 2;
72 | }
73 |
74 | // Smoothen changes in tilt angle by ramping the step size
75 | smooth_rampf(&tt->setpoint, &tt->ramped_step_size, target, step_size, 0.04, 1.5);
76 | }
77 |
78 | void torque_tilt_winddown(TorqueTilt *tt) {
79 | tt->setpoint *= 0.995;
80 | }
81 |
--------------------------------------------------------------------------------
/src/lib/circular_buffer.c:
--------------------------------------------------------------------------------
1 | // Copyright 2025 Lukas Hrazky
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #include "circular_buffer.h"
19 |
20 | #include
21 |
22 | void circular_buffer_clear(CircularBuffer *cb) {
23 | cb->head = 0;
24 | cb->tail = 0;
25 | cb->empty = true;
26 | }
27 |
28 | void circular_buffer_init(CircularBuffer *cb, size_t item_size, size_t item_number, void *buffer) {
29 | cb->buffer = buffer;
30 | cb->length = item_number;
31 | cb->item_size = item_size;
32 | circular_buffer_clear(cb);
33 | }
34 |
35 | static inline void increment(const CircularBuffer *cb, size_t *i) {
36 | ++(*i);
37 | if (*i >= cb->length) {
38 | *i -= cb->length;
39 | }
40 | }
41 |
42 | size_t circular_buffer_size(const CircularBuffer *cb) {
43 | size_t size = cb->head - cb->tail;
44 | if (size > cb->length) {
45 | return size + cb->length;
46 | } else if (size == 0 && !cb->empty) {
47 | return cb->length;
48 | }
49 | return size;
50 | }
51 |
52 | void circular_buffer_push(CircularBuffer *cb, const void *item) {
53 | if (!cb->empty && cb->head == cb->tail) {
54 | increment(cb, &cb->tail);
55 | }
56 |
57 | memcpy(cb->buffer + cb->head * cb->item_size, item, cb->item_size);
58 | increment(cb, &cb->head);
59 |
60 | cb->empty = false;
61 | }
62 |
63 | bool circular_buffer_get(const CircularBuffer *cb, size_t i, void *item) {
64 | if (i >= circular_buffer_size(cb)) {
65 | return false;
66 | }
67 |
68 | size_t offset = cb->tail + i;
69 | if (offset >= cb->length) {
70 | offset -= cb->length;
71 | }
72 | memcpy(item, cb->buffer + offset * cb->item_size, cb->item_size);
73 |
74 | return true;
75 | }
76 |
77 | bool circular_buffer_pop(CircularBuffer *cb, size_t i, void *item) {
78 | if (!circular_buffer_get(cb, i, item)) {
79 | return false;
80 | }
81 |
82 | increment(cb, &cb->tail);
83 | if (cb->tail == cb->head) {
84 | cb->empty = true;
85 | }
86 |
87 | return true;
88 | }
89 |
90 | void circular_buffer_iterate(
91 | const CircularBuffer *cb, void (*callback)(const void *item, void *data), void *data
92 | ) {
93 | if (cb->empty) {
94 | return;
95 | }
96 |
97 | size_t i = cb->tail;
98 | do {
99 | callback(&cb->buffer[i], data);
100 | increment(cb, &i);
101 | } while (i != cb->head);
102 | }
103 |
--------------------------------------------------------------------------------
/vesc_pkg_lib/examples/config/datatypes.h:
--------------------------------------------------------------------------------
1 | /*
2 | Copyright 2022 Benjamin Vedder benjamin@vedder.se
3 |
4 | This file is part of the VESC firmware.
5 |
6 | The VESC firmware is free software: you can redistribute it and/or modify
7 | it under the terms of the GNU General Public License as published by
8 | the Free Software Foundation, either version 3 of the License, or
9 | (at your option) any later version.
10 |
11 | The VESC firmware is distributed in the hope that it will be useful,
12 | but WITHOUT ANY WARRANTY; without even the implied warranty of
13 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14 | GNU General Public License for more details.
15 |
16 | You should have received a copy of the GNU General Public License
17 | along with this program. If not, see .
18 | */
19 |
20 | #ifndef DATATYPES_H_
21 | #define DATATYPES_H_
22 |
23 | #include
24 | #include
25 |
26 | typedef enum {
27 | BALANCE_PID_MODE_ANGLE = 0,
28 | BALANCE_PID_MODE_ANGLE_RATE_CASCADE
29 | } BALANCE_PID_MODE;
30 |
31 | typedef struct {
32 | BALANCE_PID_MODE pid_mode;
33 | float kp;
34 | float ki;
35 | float kd;
36 | float kp2;
37 | float ki2;
38 | float kd2;
39 | uint16_t hertz;
40 | uint16_t loop_time_filter;
41 | float fault_pitch;
42 | float fault_roll;
43 | float fault_duty;
44 | float fault_adc1;
45 | float fault_adc2;
46 | uint16_t fault_delay_pitch;
47 | uint16_t fault_delay_roll;
48 | uint16_t fault_delay_duty;
49 | uint16_t fault_delay_switch_half;
50 | uint16_t fault_delay_switch_full;
51 | uint16_t fault_adc_half_erpm;
52 | bool fault_is_dual_switch;
53 | float tiltback_duty_angle;
54 | float tiltback_duty_speed;
55 | float tiltback_duty;
56 | float tiltback_hv_angle;
57 | float tiltback_hv_speed;
58 | float tiltback_hv;
59 | float tiltback_lv_angle;
60 | float tiltback_lv_speed;
61 | float tiltback_lv;
62 | float tiltback_return_speed;
63 | float tiltback_constant;
64 | uint16_t tiltback_constant_erpm;
65 | float tiltback_variable;
66 | float tiltback_variable_max;
67 | float noseangling_speed;
68 | float startup_pitch_tolerance;
69 | float startup_roll_tolerance;
70 | float startup_speed;
71 | float deadzone;
72 | bool multi_esc;
73 | float yaw_kp;
74 | float yaw_ki;
75 | float yaw_kd;
76 | float roll_steer_kp;
77 | float roll_steer_erpm_kp;
78 | float brake_current;
79 | uint16_t brake_timeout;
80 | float yaw_current_clamp;
81 | uint16_t kd_pt1_lowpass_frequency;
82 | uint16_t kd_pt1_highpass_frequency;
83 | float kd_biquad_lowpass;
84 | float kd_biquad_highpass;
85 | float booster_angle;
86 | float booster_ramp;
87 | float booster_current;
88 | float torquetilt_start_current;
89 | float torquetilt_angle_limit;
90 | float torquetilt_on_speed;
91 | float torquetilt_off_speed;
92 | float torquetilt_strength;
93 | float torquetilt_filter;
94 | float turntilt_strength;
95 | float turntilt_angle_limit;
96 | float turntilt_start_angle;
97 | uint16_t turntilt_start_erpm;
98 | float turntilt_speed;
99 | uint16_t turntilt_erpm_boost;
100 | uint16_t turntilt_erpm_boost_end;
101 | } balance_config;
102 |
103 | // DATATYPES_H_
104 | #endif
105 |
--------------------------------------------------------------------------------
/vesc_pkg_lib/examples/config/conf/datatypes.h:
--------------------------------------------------------------------------------
1 | /*
2 | Copyright 2022 Benjamin Vedder benjamin@vedder.se
3 |
4 | This file is part of the VESC firmware.
5 |
6 | The VESC firmware is free software: you can redistribute it and/or modify
7 | it under the terms of the GNU General Public License as published by
8 | the Free Software Foundation, either version 3 of the License, or
9 | (at your option) any later version.
10 |
11 | The VESC firmware is distributed in the hope that it will be useful,
12 | but WITHOUT ANY WARRANTY; without even the implied warranty of
13 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14 | GNU General Public License for more details.
15 |
16 | You should have received a copy of the GNU General Public License
17 | along with this program. If not, see .
18 | */
19 |
20 | #ifndef DATATYPES_H_
21 | #define DATATYPES_H_
22 |
23 | #include
24 | #include
25 |
26 | typedef enum {
27 | BALANCE_PID_MODE_ANGLE = 0,
28 | BALANCE_PID_MODE_ANGLE_RATE_CASCADE
29 | } BALANCE_PID_MODE;
30 |
31 | typedef struct {
32 | BALANCE_PID_MODE pid_mode;
33 | float kp;
34 | float ki;
35 | float kd;
36 | float kp2;
37 | float ki2;
38 | float kd2;
39 | uint16_t hertz;
40 | uint16_t loop_time_filter;
41 | float fault_pitch;
42 | float fault_roll;
43 | float fault_duty;
44 | float fault_adc1;
45 | float fault_adc2;
46 | uint16_t fault_delay_pitch;
47 | uint16_t fault_delay_roll;
48 | uint16_t fault_delay_duty;
49 | uint16_t fault_delay_switch_half;
50 | uint16_t fault_delay_switch_full;
51 | uint16_t fault_adc_half_erpm;
52 | bool fault_is_dual_switch;
53 | float tiltback_duty_angle;
54 | float tiltback_duty_speed;
55 | float tiltback_duty;
56 | float tiltback_hv_angle;
57 | float tiltback_hv_speed;
58 | float tiltback_hv;
59 | float tiltback_lv_angle;
60 | float tiltback_lv_speed;
61 | float tiltback_lv;
62 | float tiltback_return_speed;
63 | float tiltback_constant;
64 | uint16_t tiltback_constant_erpm;
65 | float tiltback_variable;
66 | float tiltback_variable_max;
67 | float noseangling_speed;
68 | float startup_pitch_tolerance;
69 | float startup_roll_tolerance;
70 | float startup_speed;
71 | float deadzone;
72 | bool multi_esc;
73 | float yaw_kp;
74 | float yaw_ki;
75 | float yaw_kd;
76 | float roll_steer_kp;
77 | float roll_steer_erpm_kp;
78 | float brake_current;
79 | uint16_t brake_timeout;
80 | float yaw_current_clamp;
81 | uint16_t kd_pt1_lowpass_frequency;
82 | uint16_t kd_pt1_highpass_frequency;
83 | float kd_biquad_lowpass;
84 | float kd_biquad_highpass;
85 | float booster_angle;
86 | float booster_ramp;
87 | float booster_current;
88 | float torquetilt_start_current;
89 | float torquetilt_angle_limit;
90 | float torquetilt_on_speed;
91 | float torquetilt_off_speed;
92 | float torquetilt_strength;
93 | float torquetilt_filter;
94 | float turntilt_strength;
95 | float turntilt_angle_limit;
96 | float turntilt_start_angle;
97 | uint16_t turntilt_start_erpm;
98 | float turntilt_speed;
99 | uint16_t turntilt_erpm_boost;
100 | uint16_t turntilt_erpm_boost_end;
101 | } balance_config;
102 |
103 | // DATATYPES_H_
104 | #endif
105 |
--------------------------------------------------------------------------------
/doc/commands/index.md:
--------------------------------------------------------------------------------
1 | # Commands Reference
2 |
3 | Commands are binary messages that can be used to interact with Refloat. They can be sent from a client device (e.g. a Bluetooth-connected phone app) or from a device component connected to the VESC bus (e.g. a VESC Express, or an UART device). All messages are broadcast to all components connected to the bus on VESC level (meaning above the package level). Each component decides whether it will process a given message.
4 |
5 | On VESC level, there is a (VESC-level) command designated for package commands (it's called `COMM_CUSTOM_APP_DATA`). The payload of this command is what is sent and received by the package. For clients using a VESC API (e.g. a QML VESC Tool app) there's a function to send this command. Clients communicating with VESC outside of its ecosystem need to construct the message with its first byte set to this VESC command ID (the value of which is `36`). The rest of this documentation only deals with the payload of this VESC command and disregards the first byte.
6 |
7 | The convention for package commands is the first byte of the message is the identifier of the package interface: `package_interface_id` (also formerly called `magic` in Float). Refloat currently only processes commands with `package_interface_id` = `101` (same as Float).
8 |
9 | The second byte is the `command_id`. So each package command starts with what we could call a "command header" of the following format:
10 |
11 | | Offset | Size | Name | Description |
12 | |--------|------|------------------------|--------------------------------------|
13 | | 0 | 1 | `package_interface_id` | Identifier of the package interface. |
14 | | 1 | 1 | `command_id` | Command ID. |
15 |
16 | Messages can be freely sent both ways (from the package to anything that is listening, or from client components to the package), but typically they work on a request-response basis from client components towards the package. Some commands are one-way and don't have a response. In case of request-response, the aforementioned first two bytes are the same in the request and the response.
17 |
18 | The request and response are not linked in any way besides the first two bytes. A consequence of this together with the broadcast mechanism is that if there are two components (clients) both interacting with a third one (say, a package), both of the clients will receive responses to requests of the other client and they have no easy way to tell them apart. This can lead to some nasty issues once there are more than two components communicating via the same commands.
19 |
20 | All commands on the VESC bus are checksummed (so they shouldn't get mangled). In case of a checksum mismatch or any other communication issue, the message is dropped.
21 |
22 | ## Commands
23 |
24 | In the commands' documentation, the first two bytes with `package_interface_id` and `command_id` are omitted, so while their offsets start at 0, in the full message their data are always preceded by them.
25 |
26 | - [INFO](INFO.md)
27 | - [LIGHTS_CONTROL](LIGHTS_CONTROL.md)
28 | - [REALTIME_DATA](REALTIME_DATA.md)
29 | - [REALTIME_DATA_IDS](REALTIME_DATA_IDS.md)
30 | - [DATA_RECORD](DATA_RECORD.md)
31 | - [ALERTS_LIST](ALERTS_LIST.md)
32 | - [ALERTS_CONTROL](ALERTS_CONTROL.md)
33 |
--------------------------------------------------------------------------------
/src/brake_tilt.c:
--------------------------------------------------------------------------------
1 | // Copyright 2022 Dado Mista
2 | // Copyright 2024 Lukas Hrazky
3 | //
4 | // This file is part of the Refloat VESC package.
5 | //
6 | // Refloat VESC package is free software: you can redistribute it and/or modify
7 | // it under the terms of the GNU General Public License as published by the
8 | // Free Software Foundation, either version 3 of the License, or (at your
9 | // option) any later version.
10 | //
11 | // Refloat VESC package is distributed in the hope that it will be useful, but
12 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
13 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
14 | // more details.
15 | //
16 | // You should have received a copy of the GNU General Public License along with
17 | // this program. If not, see .
18 |
19 | #include "brake_tilt.h"
20 |
21 | #include "utils.h"
22 |
23 | #include
24 |
25 | void brake_tilt_init(BrakeTilt *bt) {
26 | bt->factor = 0.0f;
27 | brake_tilt_reset(bt);
28 | }
29 |
30 | void brake_tilt_reset(BrakeTilt *bt) {
31 | bt->ramped_step_size = 0.0f;
32 | bt->target = 0.0f;
33 | bt->setpoint = 0.0f;
34 | }
35 |
36 | void brake_tilt_configure(BrakeTilt *bt, const RefloatConfig *config) {
37 | if (config->braketilt_strength == 0) {
38 | bt->factor = 0;
39 | } else {
40 | // incorporate negative sign into braketilt factor instead of adding it each balance loop
41 | bt->factor = -(0.5f + (20 - config->braketilt_strength) / 5.0f);
42 | }
43 | }
44 |
45 | void brake_tilt_update(
46 | BrakeTilt *bt,
47 | const MotorData *motor,
48 | const ATR *atr,
49 | const RefloatConfig *config,
50 | float balance_offset
51 | ) {
52 | // braking also should cause setpoint change lift, causing a delayed lingering nose lift
53 | if (bt->factor < 0 && motor->braking && motor->abs_erpm > 2000) {
54 | // negative currents alone don't necessarily constitute active braking, look at
55 | // proportional:
56 | if (sign(balance_offset) != motor->erpm_sign) {
57 | float downhill_damper = 1;
58 | // if we're braking on a downhill we don't want braking to lift the setpoint quite as
59 | // much
60 | if ((motor->erpm > 1000 && atr->accel_diff < -1) ||
61 | (motor->erpm < -1000 && atr->accel_diff > 1)) {
62 | downhill_damper += fabsf(atr->accel_diff) / 2;
63 | }
64 | bt->target = balance_offset / bt->factor / downhill_damper;
65 | if (downhill_damper > 2) {
66 | // steep downhills, we don't enable this feature at all!
67 | bt->target = 0;
68 | }
69 | }
70 | } else {
71 | bt->target = 0;
72 | }
73 |
74 | float braketilt_step_size = atr->off_step_size / config->braketilt_lingering;
75 | if (fabsf(bt->target) > fabsf(bt->setpoint)) {
76 | braketilt_step_size = atr->on_step_size * 1.5;
77 | } else if (motor->abs_erpm < 800) {
78 | braketilt_step_size = atr->on_step_size;
79 | }
80 |
81 | if (motor->abs_erpm < 500) {
82 | braketilt_step_size /= 2;
83 | }
84 |
85 | // Smoothen changes in tilt angle by ramping the step size
86 | smooth_rampf(&bt->setpoint, &bt->ramped_step_size, bt->target, braketilt_step_size, 0.05, 1.5);
87 | }
88 |
89 | void brake_tilt_winddown(BrakeTilt *bt) {
90 | bt->setpoint *= 0.995;
91 | bt->target *= 0.99;
92 | }
93 |
--------------------------------------------------------------------------------
/doc/commands/INFO.md:
--------------------------------------------------------------------------------
1 | # Command: INFO
2 |
3 | **ID**: 0
4 |
5 | Serves for initiating communication with the package and provides information about the package.
6 |
7 | This command is versioned, the client requests a version of this command and the package returns the response of that version if it supports it. If the version is higher than what the package supports, it responds with the highest version it knows.
8 |
9 | If the client would request a version that is lower than what the package supports, the package should respond with a version `0` in its response to indicate it no longer supports a version this low.
10 |
11 | _Note: What is now referred to as version `1` of this command originally had no notion of versioning,but the mechanism is designed so that the version `1` is compatible with the original command._
12 |
13 | ## Request
14 |
15 | | Offset | Size | Name | Mandatory | Description |
16 | |--------|------|-----------|-----------|---------------|
17 | | 0 | 1 | `version` | No | Requested version of the INFO command. In case the package doesn't support version this high, it shall respond with the highest version of the command it supports. Default value: `1` |
18 | | 1 | 1 | `flags` | No | Only for version 2. Flags for toggling extra information in the response (currently unused). |
19 |
20 | ## Response
21 |
22 | ### version 1
23 |
24 | | Offset | Size | Name | Description |
25 | |--------|------|-----------------------|---------------|
26 | | 0 | 1 | `major_minor_version` | Package major and minor version encoded in a single number: `major * 10 + minor` |
27 | | 1 | 1 | `build_number` | Always `1`. |
28 | | 2 | 1 | `leds_type` | LEDs type:
`0`: None
`1`: Internal
`3`: External
_Note: In this version, "External" is `3` and `2` is never returned._ |
29 |
30 | ### version 2
31 |
32 | | Offset | Size | Name | Description |
33 | |--------|------|--------------------------|---------------|
34 | | 0 | 1 | `version` | The actual version of this `INFO` command response, for the case a lower than requested version is returned.
_Note: version 1 does not return this, but its first byte in the response is always higher than 10, which can be used to distinguish the version._ |
35 | | 1 | 1 | `flags` | The `flags` from the request repeated in the response, to indicate which extra data are present. |
36 | | 2 | 20 | `package_name` | The package name string. Zero-padded to 20 bytes, not zero-terminated in case all 20 bytes are used. |
37 | | 22 | 1 | `package_major_version` | Major version of the package. |
38 | | 23 | 1 | `package_minor_version` | Minor version of the package. |
39 | | 24 | 1 | `package_patch_version` | Patch version of the package. |
40 | | 25 | 20 | `package_version_suffix` | An optional package version suffix string. Zero-padded to 20 bytes, not zero-terminated in case all 20 bytes are used. |
41 | | 45 | 4 | `git_hash` | First 4 bytes of the git hash from which the package was built. |
42 | | 49 | 4 | `tick_rate` | Tick rate of the system in Hz. This number can be used to convert time measured in ticks in other commands (namely `REALTIME_DATA`) to seconds by dividing by this number. Currently the tick rate for VESC is always `10000`. |
43 | | 53 | 4 | `capabilities` | Capability flags of the package:
`0x1`: LED lighting.
`0x2`: LED lighting is external through a module.
`0x80000000`: Data Recording. See the [Realtime Value Tracking](../realtime_value_tracking.md) page for details. |
44 | | 57 | 1 | `extra_flags` | Extra flags:
[empty] |
45 |
--------------------------------------------------------------------------------
/vesc_pkg_lib/examples/config/code.c:
--------------------------------------------------------------------------------
1 | /*
2 | Copyright 2022 Benjamin Vedder benjamin@vedder.se
3 |
4 | This file is part of the VESC firmware.
5 |
6 | The VESC firmware is free software: you can redistribute it and/or modify
7 | it under the terms of the GNU General Public License as published by
8 | the Free Software Foundation, either version 3 of the License, or
9 | (at your option) any later version.
10 |
11 | The VESC firmware is distributed in the hope that it will be useful,
12 | but WITHOUT ANY WARRANTY; without even the implied warranty of
13 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14 | GNU General Public License for more details.
15 |
16 | You should have received a copy of the GNU General Public License
17 | along with this program. If not, see .
18 | */
19 |
20 | #include "vesc_c_if.h"
21 |
22 | #include "conf/datatypes.h"
23 | #include "conf/confparser.h"
24 | #include "conf/confxml.h"
25 |
26 | #include
27 |
28 | HEADER
29 |
30 | typedef struct {
31 | balance_config balance_conf;
32 | } data;
33 |
34 | static int get_cfg(uint8_t *buffer, bool is_default) {
35 | data *d = (data*)ARG;
36 | balance_config cfg = d->balance_conf;
37 |
38 | if (is_default) {
39 | confparser_set_defaults_balance_config(&cfg);
40 | }
41 |
42 | return confparser_serialize_balance_config(buffer, &cfg);
43 | }
44 |
45 | static bool set_cfg(uint8_t *buffer) {
46 | data *d = (data*)ARG;
47 | bool res = confparser_deserialize_balance_config(buffer, &(d->balance_conf));
48 |
49 | // Store to EEPROM
50 | if (res) {
51 | uint32_t ints = sizeof(balance_config) / 4 + 1;
52 | uint32_t buffer[ints];
53 | bool write_ok = true;
54 | memcpy(buffer, &(d->balance_conf), sizeof(balance_config));
55 | for (uint32_t i = 0;i < ints;i++) {
56 | eeprom_var v;
57 | v.as_u32 = buffer[i];
58 | if (!VESC_IF->store_eeprom_var(&v, i + 1)) {
59 | write_ok = false;
60 | break;
61 | }
62 | }
63 |
64 | if (write_ok) {
65 | eeprom_var v;
66 | v.as_u32 = BALANCE_CONFIG_SIGNATURE;
67 | VESC_IF->store_eeprom_var(&v, 0);
68 | }
69 | }
70 |
71 | return res;
72 | }
73 |
74 | static int get_cfg_xml(uint8_t **buffer) {
75 | // Note: As the address of data_balance_config_ is not known
76 | // at compile time it will be relative to where it is in the
77 | // linked binary. Therefore we add PROG_ADDR to it so that it
78 | // points to where it ends up on the STM32.
79 | *buffer = data_balance_config_ + PROG_ADDR;
80 | return DATA_BALANCE_CONFIG__SIZE;
81 | }
82 |
83 | // Called when code is stopped
84 | static void stop(void *arg) {
85 | (void)arg;
86 | VESC_IF->conf_custom_clear_configs();
87 | }
88 |
89 | INIT_FUN(lib_info *info) {
90 | INIT_START
91 |
92 | data *d = VESC_IF->malloc(sizeof(data));
93 | memset(d, 0, sizeof(data));
94 |
95 | // Read config from EEPROM if signature is correct
96 | eeprom_var v;
97 | uint32_t ints = sizeof(balance_config) / 4 + 1;
98 | uint32_t buffer[ints];
99 | bool read_ok = VESC_IF->read_eeprom_var(&v, 0);
100 | if (read_ok && v.as_u32 == BALANCE_CONFIG_SIGNATURE) {
101 | for (uint32_t i = 0;i < ints;i++) {
102 | if (!VESC_IF->read_eeprom_var(&v, i + 1)) {
103 | read_ok = false;
104 | break;
105 | }
106 | buffer[i] = v.as_u32;
107 | }
108 | } else {
109 | read_ok = false;
110 | }
111 |
112 | if (read_ok) {
113 | memcpy(&(d->balance_conf), buffer, sizeof(balance_config));
114 | } else {
115 | confparser_set_defaults_balance_config(&(d->balance_conf));
116 | }
117 |
118 | info->stop_fun = stop;
119 | info->arg = d;
120 |
121 | VESC_IF->conf_custom_add_config(get_cfg, set_cfg, get_cfg_xml);
122 |
123 | return true;
124 | }
125 |
126 |
--------------------------------------------------------------------------------
/src/alert_tracker.c:
--------------------------------------------------------------------------------
1 | // Copyright 2025 Lukas Hrazky
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #include "alert_tracker.h"
19 |
20 | static uint32_t alert_id_to_mask(AlertId alert_id) {
21 | return 1 << (alert_id - 1);
22 | }
23 |
24 | static const AlertProperties alert_properties[] = {
25 | [ALERT_FW_FAULT] = {.type = ATYPE_FATAL},
26 | };
27 |
28 | const AlertProperties *alert_tracker_properties(AlertId alert_id) {
29 | return &alert_properties[alert_id];
30 | }
31 |
32 | void alert_tracker_init(AlertTracker *at) {
33 | at->persistent_fatal_error = true;
34 |
35 | at->active_alert_mask = 0;
36 | at->new_active_alert_mask = 0;
37 | at->fw_fault_code = FAULT_CODE_NONE;
38 | at->fatal_error = false;
39 |
40 | circular_buffer_init(
41 | &at->alert_buffer, sizeof(AlertRecord), ALERT_TRACKER_SIZE, &at->alert_buffer_array
42 | );
43 | }
44 |
45 | void alert_tracker_configure(AlertTracker *at, const RefloatConfig *config) {
46 | at->persistent_fatal_error = config->persistent_fatal_error;
47 | }
48 |
49 | void alert_tracker_add(AlertTracker *at, const Time *time, uint8_t id, uint8_t code) {
50 | uint32_t mask = alert_id_to_mask(ALERT_FW_FAULT);
51 | bool already_active = at->active_alert_mask & mask;
52 | if (id == ALERT_FW_FAULT) {
53 | already_active = already_active && code == at->fw_fault_code;
54 | at->fw_fault_code = code;
55 | }
56 |
57 | if (!already_active) {
58 | AlertRecord alert = {.time = time->now, .id = id, .code = code, .active = true};
59 | circular_buffer_push(&at->alert_buffer, &alert);
60 | }
61 |
62 | if (alert_tracker_properties(id)->type == ATYPE_FATAL) {
63 | at->fatal_error = true;
64 | }
65 |
66 | at->new_active_alert_mask |= mask;
67 | }
68 |
69 | void alert_tracker_finalize(AlertTracker *at, const Time *time) {
70 | // Check for alerts that ended and create a record of it
71 | bool clear_fatal = !at->persistent_fatal_error;
72 | for (uint8_t id = 1; id <= ALERT_LAST; ++id) {
73 | uint32_t mask = alert_id_to_mask(id);
74 | if (at->active_alert_mask & mask && !(at->new_active_alert_mask & mask)) {
75 | AlertRecord alert = {.time = time->now, .id = id, .code = 0, .active = false};
76 | circular_buffer_push(&at->alert_buffer, &alert);
77 | if (id == ALERT_FW_FAULT) {
78 | at->fw_fault_code = 0;
79 | }
80 | }
81 |
82 | if (at->active_alert_mask & mask && alert_tracker_properties(id)->type == ATYPE_FATAL) {
83 | clear_fatal = false;
84 | }
85 | }
86 |
87 | at->active_alert_mask = at->new_active_alert_mask;
88 | at->new_active_alert_mask = 0;
89 |
90 | at->fatal_error &= !clear_fatal;
91 | }
92 |
93 | bool alert_tracker_is_alert_active(AlertTracker *at, AlertId alert) {
94 | return at->active_alert_mask & alert_id_to_mask(alert);
95 | }
96 |
97 | void alert_tracker_clear_fatal(AlertTracker *at) {
98 | at->fatal_error = false;
99 | }
100 |
--------------------------------------------------------------------------------
/vesc_pkg_lib/stdperiph_stm32f4/CMSIS/include/arm_const_structs.h:
--------------------------------------------------------------------------------
1 | /* ----------------------------------------------------------------------
2 | * Copyright (C) 2010-2013 ARM Limited. All rights reserved.
3 | *
4 | * $Date: 17. January 2013
5 | * $Revision: V1.4.1
6 | *
7 | * Project: CMSIS DSP Library
8 | * Title: arm_const_structs.h
9 | *
10 | * Description: This file has constant structs that are initialized for
11 | * user convenience. For example, some can be given as
12 | * arguments to the arm_cfft_f32() function.
13 | *
14 | * Target Processor: Cortex-M4/Cortex-M3
15 | *
16 | * Redistribution and use in source and binary forms, with or without
17 | * modification, are permitted provided that the following conditions
18 | * are met:
19 | * - Redistributions of source code must retain the above copyright
20 | * notice, this list of conditions and the following disclaimer.
21 | * - Redistributions in binary form must reproduce the above copyright
22 | * notice, this list of conditions and the following disclaimer in
23 | * the documentation and/or other materials provided with the
24 | * distribution.
25 | * - Neither the name of ARM LIMITED nor the names of its contributors
26 | * may be used to endorse or promote products derived from this
27 | * software without specific prior written permission.
28 | *
29 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
30 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
31 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
32 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
33 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
34 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
35 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
36 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
37 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
38 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
39 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
40 | * POSSIBILITY OF SUCH DAMAGE.
41 | * -------------------------------------------------------------------- */
42 |
43 | #ifndef _ARM_CONST_STRUCTS_H
44 | #define _ARM_CONST_STRUCTS_H
45 |
46 | #include "arm_math.h"
47 | #include "arm_common_tables.h"
48 |
49 | const arm_cfft_instance_f32 arm_cfft_sR_f32_len16 = {
50 | 16, twiddleCoef_16, armBitRevIndexTable16, ARMBITREVINDEXTABLE__16_TABLE_LENGTH
51 | };
52 |
53 | const arm_cfft_instance_f32 arm_cfft_sR_f32_len32 = {
54 | 32, twiddleCoef_32, armBitRevIndexTable32, ARMBITREVINDEXTABLE__32_TABLE_LENGTH
55 | };
56 |
57 | const arm_cfft_instance_f32 arm_cfft_sR_f32_len64 = {
58 | 64, twiddleCoef_64, armBitRevIndexTable64, ARMBITREVINDEXTABLE__64_TABLE_LENGTH
59 | };
60 |
61 | const arm_cfft_instance_f32 arm_cfft_sR_f32_len128 = {
62 | 128, twiddleCoef_128, armBitRevIndexTable128, ARMBITREVINDEXTABLE_128_TABLE_LENGTH
63 | };
64 |
65 | const arm_cfft_instance_f32 arm_cfft_sR_f32_len256 = {
66 | 256, twiddleCoef_256, armBitRevIndexTable256, ARMBITREVINDEXTABLE_256_TABLE_LENGTH
67 | };
68 |
69 | const arm_cfft_instance_f32 arm_cfft_sR_f32_len512 = {
70 | 512, twiddleCoef_512, armBitRevIndexTable512, ARMBITREVINDEXTABLE_512_TABLE_LENGTH
71 | };
72 |
73 | const arm_cfft_instance_f32 arm_cfft_sR_f32_len1024 = {
74 | 1024, twiddleCoef_1024, armBitRevIndexTable1024, ARMBITREVINDEXTABLE1024_TABLE_LENGTH
75 | };
76 |
77 | const arm_cfft_instance_f32 arm_cfft_sR_f32_len2048 = {
78 | 2048, twiddleCoef_2048, armBitRevIndexTable2048, ARMBITREVINDEXTABLE2048_TABLE_LENGTH
79 | };
80 |
81 | const arm_cfft_instance_f32 arm_cfft_sR_f32_len4096 = {
82 | 4096, twiddleCoef_4096, armBitRevIndexTable4096, ARMBITREVINDEXTABLE4096_TABLE_LENGTH
83 | };
84 |
85 | #endif
86 |
--------------------------------------------------------------------------------
/src/remote.c:
--------------------------------------------------------------------------------
1 | // Copyright 2025 Lukas Hrazky
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #include "remote.h"
19 |
20 | #include "utils.h"
21 |
22 | void remote_init(Remote *remote) {
23 | remote->input = 0;
24 | remote->ramped_step_size = 0;
25 | remote->setpoint = 0;
26 | }
27 |
28 | void remote_reset(Remote *remote) {
29 | remote->setpoint = 0;
30 | remote->ramped_step_size = 0;
31 | }
32 |
33 | void remote_configure(Remote *remote, const RefloatConfig *config) {
34 | remote->step_size = config->inputtilt_speed / config->hertz;
35 | }
36 |
37 | void remote_input(Remote *remote, const RefloatConfig *config) {
38 | bool connected = false;
39 | float value = 0;
40 |
41 | switch (config->inputtilt_remote_type) {
42 | case (INPUTTILT_PPM):
43 | value = VESC_IF->get_ppm();
44 | connected = VESC_IF->get_ppm_age() < 1;
45 | break;
46 | case (INPUTTILT_UART): {
47 | remote_state remote = VESC_IF->get_remote_state();
48 | value = remote.js_y;
49 | connected = remote.age_s < 1;
50 | break;
51 | }
52 | case (INPUTTILT_NONE):
53 | break;
54 | }
55 |
56 | if (!connected) {
57 | remote->input = 0;
58 | return;
59 | }
60 |
61 | float deadband = config->inputtilt_deadband;
62 | if (fabsf(value) < deadband) {
63 | value = 0.0;
64 | } else {
65 | value = sign(value) * (fabsf(value) - deadband) / (1 - deadband);
66 | }
67 |
68 | if (config->inputtilt_invert_throttle) {
69 | value = -value;
70 | }
71 |
72 | remote->input = value;
73 | }
74 |
75 | void remote_update(Remote *remote, const State *state, const RefloatConfig *config) {
76 | float target = remote->input * config->inputtilt_angle_limit;
77 |
78 | if (state->darkride) {
79 | target = -target;
80 | }
81 |
82 | float target_diff = target - remote->setpoint;
83 |
84 | // Smoothen changes in tilt angle by ramping the step size
85 | const float smoothing_factor = 0.02;
86 |
87 | // Within X degrees of Target Angle, start ramping down step size
88 | if (fabsf(target_diff) < 2.0f) {
89 | // Target step size is reduced the closer to center you are (needed for smoothly
90 | // transitioning away from center)
91 | remote->ramped_step_size = smoothing_factor * remote->step_size * target_diff / 2 +
92 | (1 - smoothing_factor) * remote->ramped_step_size;
93 | // Linearly ramped down step size is provided as minimum to prevent overshoot
94 | float centering_step_size =
95 | fminf(fabsf(remote->ramped_step_size), fabsf(target_diff / 2) * remote->step_size) *
96 | sign(target_diff);
97 | if (fabsf(target_diff) < fabsf(centering_step_size)) {
98 | remote->setpoint = target;
99 | } else {
100 | remote->setpoint += centering_step_size;
101 | }
102 | } else {
103 | // Ramp up step size until the configured tilt speed is reached
104 | remote->ramped_step_size = smoothing_factor * remote->step_size * sign(target_diff) +
105 | (1 - smoothing_factor) * remote->ramped_step_size;
106 | remote->setpoint += remote->ramped_step_size;
107 | }
108 | }
109 |
--------------------------------------------------------------------------------
/src/state.c:
--------------------------------------------------------------------------------
1 | // Copyright 2024 Lukas Hrazky
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #include "state.h"
19 |
20 | void state_init(State *state) {
21 | state->state = STATE_STARTUP;
22 | state->mode = MODE_NORMAL;
23 | state->sat = SAT_NONE;
24 | state->stop_condition = STOP_NONE;
25 | state->charging = false;
26 | state->wheelslip = false;
27 | state->darkride = false;
28 | }
29 |
30 | void state_stop(State *state, StopCondition stop_condition) {
31 | state->state = STATE_READY;
32 | state->stop_condition = stop_condition;
33 | state->wheelslip = false;
34 | }
35 |
36 | void state_engage(State *state) {
37 | state->state = STATE_RUNNING;
38 | state->sat = SAT_CENTERING;
39 | state->stop_condition = STOP_NONE;
40 | }
41 |
42 | void state_set_disabled(State *state, bool disabled) {
43 | if (state->state != STATE_RUNNING && disabled) {
44 | state->state = STATE_DISABLED;
45 | } else if (state->state == STATE_DISABLED && !disabled) {
46 | state->state = STATE_STARTUP;
47 | }
48 | }
49 |
50 | uint8_t state_compat(const State *state) {
51 | if (state->charging) {
52 | return 14; // CHARGING
53 | }
54 |
55 | switch (state->state) {
56 | case STATE_DISABLED:
57 | return 15; // DISABLED
58 | case STATE_STARTUP:
59 | return 0; // STARTUP
60 | case STATE_READY:
61 | switch (state->stop_condition) {
62 | case STOP_NONE:
63 | return 11; // FAULT_STARTUP
64 | case STOP_PITCH:
65 | return 6; // FAULT_ANGLE_PITCH
66 | case STOP_ROLL:
67 | return 7; // FAULT_ANGLE_ROLL
68 | case STOP_SWITCH_HALF:
69 | return 8; // FAULT_SWITCH_HALF
70 | case STOP_SWITCH_FULL:
71 | return 9; // FAULT_SWITCH_FULL
72 | case STOP_REVERSE_STOP:
73 | return 12; // FAULT_REVERSE
74 | case STOP_QUICKSTOP:
75 | return 13; // FAULT_QUICKSTOP
76 | }
77 | return 11; // FAULT_STARTUP
78 | case STATE_RUNNING:
79 | if (state->sat > SAT_PB_DUTY) {
80 | return 2; // RUNNING_TILTBACK
81 | } else if (state->wheelslip) {
82 | return 3; // RUNNING_WHEELSLIP
83 | } else if (state->darkride) {
84 | return 4; // RUNNING_UPSIDEDOWN
85 | } else if (state->mode == MODE_FLYWHEEL) {
86 | return 5; // RUNNING_FLYWHEEL
87 | }
88 | return 1; // RUNNING
89 | }
90 | return 0; // STARTUP
91 | }
92 |
93 | uint8_t sat_compat(const State *state) {
94 | switch (state->sat) {
95 | case SAT_CENTERING:
96 | return 0; // CENTERING
97 | case SAT_REVERSESTOP:
98 | return 1; // REVERSESTOP
99 | case SAT_NONE:
100 | return 2; // TILTBACK_NONE
101 | case SAT_PB_DUTY:
102 | return 3; // TILTBACK_DUTY
103 | case SAT_PB_HIGH_VOLTAGE:
104 | return 4; // TILTBACK_HV
105 | case SAT_PB_LOW_VOLTAGE:
106 | return 5; // TILTBACK_LV
107 | case SAT_PB_TEMPERATURE:
108 | return 6; // TILTBACK_TEMP
109 | case SAT_PB_SPEED:
110 | return 7;
111 | case SAT_PB_ERROR:
112 | return 8;
113 | }
114 | return 0; // CENTERING
115 | }
116 |
--------------------------------------------------------------------------------
/vesc_pkg_lib/examples/speed_test/README.md:
--------------------------------------------------------------------------------
1 | # Speed Test
2 |
3 | C code for the speed test example in lisp. This is the corresponding code in lisp that loads the compiled binary of this example:
4 |
5 | ```clj
6 | (def example [
7 | 0x00 0x00 0x00 0x00 0x0a 0x4b 0x0b 0x49 0x0b 0x48 0x10 0xb5 0x7b 0x44 0x07 0x4c 0x1b 0x68 0x23 0x68
8 | 0x79 0x44 0x78 0x44 0x98 0x47 0x08 0x49 0x08 0x48 0x23 0x68 0x79 0x44 0x78 0x44 0x98 0x47 0x01 0x20
9 | 0x10 0xbd 0x00 0xbf 0x00 0xf8 0x00 0x10 0xf0 0xff 0xff 0xff 0xc1 0x00 0x00 0x00 0x46 0x00 0x00 0x00
10 | 0x05 0x01 0x00 0x00 0x46 0x00 0x00 0x00 0x00 0x00 0x00 0x00 0x00 0x00 0x00 0x00 0x00 0x00 0x00 0x00
11 | 0x43 0x20 0x54 0x61 0x6b 0x52 0x65 0x73 0x3a 0x20 0x25 0x64 0x00 0x00 0x00 0x00 0x65 0x78 0x74 0x2d
12 | 0x64 0x65 0x63 0x2d 0x63 0x6e 0x74 0x00 0x65 0x78 0x74 0x2d 0x74 0x61 0x6b 0x00 0x82 0xb0 0x01 0x90
13 | 0x01 0x98 0x18 0xb1 0x01 0x98 0x01 0x38 0x02 0xb0 0xf7 0xe7 0x02 0xb0 0x70 0x47 0x30 0xb5 0x85 0xb0
14 | 0x03 0x90 0x02 0x91 0x01 0x92 0x02 0x9a 0x03 0x9b 0x9a 0x42 0x1a 0xda 0x03 0x98 0x02 0x99 0x01 0x9a
15 | 0x01 0x38 0xff 0xf7 0xf1 0xff 0x04 0x46 0x02 0x98 0x01 0x99 0x03 0x9a 0x01 0x38 0xff 0xf7 0xea 0xff
16 | 0x05 0x46 0x01 0x98 0x03 0x99 0x02 0x9a 0x01 0x38 0xff 0xf7 0xe3 0xff 0x29 0x46 0x02 0x46 0x20 0x46
17 | 0x05 0xb0 0xbd 0xe8 0x30 0x40 0xdb 0xe7 0x01 0x98 0x05 0xb0 0x30 0xbd 0x00 0x00 0x70 0xb5 0x01 0x29
18 | 0x2d 0xed 0x02 0x8b 0x05 0x46 0x10 0x4c 0x18 0xd1 0xe3 0x6f 0x00 0x68 0x98 0x47 0xa0 0xb1 0xd4 0xf8
19 | 0xac 0x30 0x98 0x47 0x63 0x6e 0x28 0x68 0xb0 0xee 0x40 0x8a 0x98 0x47 0xff 0xf7 0xb9 0xff 0xd4 0xf8
20 | 0xac 0x30 0x98 0x47 0x30 0xee 0x48 0x0a 0xbd 0xec 0x02 0x8b 0xe3 0x6c 0xbd 0xe8 0x70 0x40 0x18 0x47
21 | 0xbd 0xec 0x02 0x8b 0xd4 0xf8 0x94 0x00 0x70 0xbd 0x00 0xbf 0x00 0xf8 0x00 0x10 0x2d 0xe9 0xf0 0x41
22 | 0x03 0x29 0x2d 0xed 0x02 0x8b 0x05 0x46 0x1e 0x4c 0x35 0xd1 0xe3 0x6f 0x00 0x68 0x98 0x47 0x00 0x28
23 | 0x30 0xd0 0xe3 0x6f 0x68 0x68 0x98 0x47 0x60 0xb3 0xe3 0x6f 0xa8 0x68 0x98 0x47 0x40 0xb3 0xd4 0xf8
24 | 0xac 0x30 0x98 0x47 0x63 0x6e 0x28 0x68 0xb0 0xee 0x40 0x8a 0x98 0x47 0x63 0x6e 0x06 0x46 0x68 0x68
25 | 0x98 0x47 0x63 0x6e 0x07 0x46 0xa8 0x68 0x98 0x47 0x39 0x46 0x02 0x46 0x30 0x46 0xff 0xf7 0x86 0xff
26 | 0xd4 0xf8 0xac 0x30 0x05 0x46 0x98 0x47 0x0b 0x48 0xd4 0xf8 0xb4 0x30 0xf0 0xee 0x40 0x8a 0x29 0x46
27 | 0x78 0x44 0x98 0x47 0x38 0xee 0xc8 0x0a 0xbd 0xec 0x02 0x8b 0xe3 0x6c 0xbd 0xe8 0xf0 0x41 0x18 0x47
28 | 0xbd 0xec 0x02 0x8b 0xd4 0xf8 0x94 0x00 0xbd 0xe8 0xf0 0x81 0x00 0xf8 0x00 0x10 0xbc 0xfe 0xff 0xff
29 | ])
30 |
31 | ; Provides ext-dec-cnt and ext-tak which are implemented as recursive functions in C
32 | ; like below. They take the same arguments, but return the number of seconds they took
33 | ; to run
34 | (load-native-lib example)
35 |
36 | (defun dec-cnt (x)
37 | (if (= x 0) 0 (dec-cnt (- x 1)))
38 | )
39 |
40 | ; Seems to run faster using match instead of if
41 | (defun dec-cnt2 (x)
42 | (match x (0 0) (_ (dec-cnt2 (- x 1))))
43 | )
44 |
45 | (defun tak (x y z)
46 | (if (>= y x)
47 | z
48 | (tak
49 | (tak (- x 1) y z)
50 | (tak (- y 1) z x)
51 | (tak (- z 1) x y)
52 | )))
53 |
54 | (print "\nTesting dec-cnt...")
55 | (looprange i 0 2
56 | (progn
57 | (print (str-from-n (+ i 1) "Try %d"))
58 | (print (str-from-n (ext-dec-cnt 100000) "C Time: %.5f s"))
59 | (define start (systime))
60 | (dec-cnt2 100000)
61 | (def time (secs-since start))
62 | (print (str-from-n time "LBM Time: %.3f s"))
63 | (print (str-from-n (/ time (ext-dec-cnt 100000)) "C Speed Diff: %.1f times"))
64 | (sleep 1)
65 | ))
66 |
67 | (print "\nTesting tak...")
68 | (looprange i 0 2
69 | (progn
70 | (print (str-from-n (+ i 1) "Try %d"))
71 | (print (str-from-n (ext-tak 18 12 6) "C Time: %.5f s"))
72 | (define start (systime))
73 | (define takres (tak 18 12 6))
74 | (def time (secs-since start))
75 | (print (str-from-n time "LBM Time: %.3f s"))
76 | (print (str-from-n (/ time (ext-tak 18 12 6)) "C Speed Diff: %.1f times"))
77 | (sleep 1)
78 | ))
79 | ```
--------------------------------------------------------------------------------
/vesc_pkg_lib/st_types.h:
--------------------------------------------------------------------------------
1 | /*
2 | Copyright 2022 Benjamin Vedder benjamin@vedder.se
3 |
4 | This file is part of the VESC firmware.
5 |
6 | The VESC firmware is free software: you can redistribute it and/or modify
7 | it under the terms of the GNU General Public License as published by
8 | the Free Software Foundation, either version 3 of the License, or
9 | (at your option) any later version.
10 |
11 | The VESC firmware is distributed in the hope that it will be useful,
12 | but WITHOUT ANY WARRANTY; without even the implied warranty of
13 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14 | GNU General Public License for more details.
15 |
16 | You should have received a copy of the GNU General Public License
17 | along with this program. If not, see .
18 | */
19 |
20 | #ifndef ST_TYPES_H
21 | #define ST_TYPES_H
22 |
23 | #include
24 | #include
25 | #include "system_stm32f4xx.h"
26 | #include "stm32f4xx_conf.h"
27 |
28 | typedef struct {
29 | volatile uint32_t MODER;
30 | volatile uint32_t OTYPER;
31 | volatile uint32_t OSPEEDR;
32 | volatile uint32_t PUPDR;
33 | volatile uint32_t IDR;
34 | volatile uint32_t ODR;
35 | volatile union {
36 | uint32_t W;
37 | struct {
38 | uint16_t set;
39 | uint16_t clear;
40 | } H;
41 | } BSRR;
42 | volatile uint32_t LCKR;
43 | volatile uint32_t AFRL;
44 | volatile uint32_t AFRH;
45 | volatile uint32_t BRR;
46 | } stm32_gpio_t;
47 |
48 | #undef GPIOA
49 | #undef GPIOB
50 | #undef GPIOC
51 | #undef GPIOD
52 | #undef GPIOE
53 | #undef GPIOF
54 | #undef GPIOG
55 | #undef GPIOH
56 | #undef GPIOI
57 |
58 | #define GPIOA ((stm32_gpio_t *)GPIOA_BASE)
59 | #define GPIOB ((stm32_gpio_t *)GPIOB_BASE)
60 | #define GPIOC ((stm32_gpio_t *)GPIOC_BASE)
61 | #define GPIOD ((stm32_gpio_t *)GPIOD_BASE)
62 | #define GPIOE ((stm32_gpio_t *)GPIOE_BASE)
63 | #define GPIOF ((stm32_gpio_t *)GPIOF_BASE)
64 | #define GPIOG ((stm32_gpio_t *)GPIOG_BASE)
65 | #define GPIOH ((stm32_gpio_t *)GPIOH_BASE)
66 | #define GPIOI ((stm32_gpio_t *)GPIOI_BASE)
67 |
68 | #define PAL_STM32_MODE_MASK (3U << 0U)
69 | #define PAL_STM32_MODE_INPUT (0U << 0U)
70 | #define PAL_STM32_MODE_OUTPUT (1U << 0U)
71 | #define PAL_STM32_MODE_ALTERNATE (2U << 0U)
72 | #define PAL_STM32_MODE_ANALOG (3U << 0U)
73 |
74 | #define PAL_STM32_OTYPE_MASK (1U << 2U)
75 | #define PAL_STM32_OTYPE_PUSHPULL (0U << 2U)
76 | #define PAL_STM32_OTYPE_OPENDRAIN (1U << 2U)
77 |
78 | #define PAL_STM32_OSPEED_MASK (3U << 3U)
79 | #define PAL_STM32_OSPEED_LOWEST (0U << 3U)
80 | #if defined(STM32F0XX) || defined(STM32F30X) || defined(STM32F37X)
81 | #define PAL_STM32_OSPEED_MID (1U << 3U)
82 | #else
83 | #define PAL_STM32_OSPEED_MID1 (1U << 3U)
84 | #define PAL_STM32_OSPEED_MID2 (2U << 3U)
85 | #endif
86 | #define PAL_STM32_OSPEED_HIGHEST (3U << 3U)
87 |
88 | #define PAL_STM32_PUDR_MASK (3U << 5U)
89 | #define PAL_STM32_PUDR_FLOATING (0U << 5U)
90 | #define PAL_STM32_PUDR_PULLUP (1U << 5U)
91 | #define PAL_STM32_PUDR_PULLDOWN (2U << 5U)
92 |
93 | #define PAL_STM32_ALTERNATE_MASK (15U << 7U)
94 | #define PAL_STM32_ALTERNATE(n) ((n) << 7U)
95 |
96 | #define PAL_STM32_MODE_MASK (3U << 0U)
97 | #define PAL_STM32_MODE_INPUT (0U << 0U)
98 | #define PAL_STM32_MODE_OUTPUT (1U << 0U)
99 | #define PAL_STM32_MODE_ALTERNATE (2U << 0U)
100 | #define PAL_STM32_MODE_ANALOG (3U << 0U)
101 |
102 | #define PAL_STM32_ALTERNATE(n) ((n) << 7U)
103 |
104 | #define PAL_MODE_ALTERNATE(n) (PAL_STM32_MODE_ALTERNATE | PAL_STM32_ALTERNATE(n))
105 |
106 | #endif // ST_TYPES_H
107 |
108 |
--------------------------------------------------------------------------------
/vesc_pkg_lib/stdperiph_stm32f4/inc/stm32f4xx_wwdg.h:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * @file stm32f4xx_wwdg.h
4 | * @author MCD Application Team
5 | * @version V1.6.0
6 | * @date 10-July-2015
7 | * @brief This file contains all the functions prototypes for the WWDG firmware
8 | * library.
9 | ******************************************************************************
10 | * @attention
11 | *
12 | * © COPYRIGHT 2015 STMicroelectronics
13 | *
14 | * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
15 | * You may not use this file except in compliance with the License.
16 | * You may obtain a copy of the License at:
17 | *
18 | * http://www.st.com/software_license_agreement_liberty_v2
19 | *
20 | * Unless required by applicable law or agreed to in writing, software
21 | * distributed under the License is distributed on an "AS IS" BASIS,
22 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
23 | * See the License for the specific language governing permissions and
24 | * limitations under the License.
25 | *
26 | ******************************************************************************
27 | */
28 |
29 | /* Define to prevent recursive inclusion -------------------------------------*/
30 | #ifndef __STM32F4xx_WWDG_H
31 | #define __STM32F4xx_WWDG_H
32 |
33 | #ifdef __cplusplus
34 | extern "C" {
35 | #endif
36 |
37 | /* Includes ------------------------------------------------------------------*/
38 | #include "stm32f4xx.h"
39 |
40 | /** @addtogroup STM32F4xx_StdPeriph_Driver
41 | * @{
42 | */
43 |
44 | /** @addtogroup WWDG
45 | * @{
46 | */
47 |
48 | /* Exported types ------------------------------------------------------------*/
49 | /* Exported constants --------------------------------------------------------*/
50 |
51 | /** @defgroup WWDG_Exported_Constants
52 | * @{
53 | */
54 |
55 | /** @defgroup WWDG_Prescaler
56 | * @{
57 | */
58 |
59 | #define WWDG_Prescaler_1 ((uint32_t)0x00000000)
60 | #define WWDG_Prescaler_2 ((uint32_t)0x00000080)
61 | #define WWDG_Prescaler_4 ((uint32_t)0x00000100)
62 | #define WWDG_Prescaler_8 ((uint32_t)0x00000180)
63 | #define IS_WWDG_PRESCALER(PRESCALER) (((PRESCALER) == WWDG_Prescaler_1) || \
64 | ((PRESCALER) == WWDG_Prescaler_2) || \
65 | ((PRESCALER) == WWDG_Prescaler_4) || \
66 | ((PRESCALER) == WWDG_Prescaler_8))
67 | #define IS_WWDG_WINDOW_VALUE(VALUE) ((VALUE) <= 0x7F)
68 | #define IS_WWDG_COUNTER(COUNTER) (((COUNTER) >= 0x40) && ((COUNTER) <= 0x7F))
69 |
70 | /**
71 | * @}
72 | */
73 |
74 | /**
75 | * @}
76 | */
77 |
78 | /* Exported macro ------------------------------------------------------------*/
79 | /* Exported functions --------------------------------------------------------*/
80 |
81 | /* Function used to set the WWDG configuration to the default reset state ****/
82 | void WWDG_DeInit(void);
83 |
84 | /* Prescaler, Refresh window and Counter configuration functions **************/
85 | void WWDG_SetPrescaler(uint32_t WWDG_Prescaler);
86 | void WWDG_SetWindowValue(uint8_t WindowValue);
87 | void WWDG_EnableIT(void);
88 | void WWDG_SetCounter(uint8_t Counter);
89 |
90 | /* WWDG activation function ***************************************************/
91 | void WWDG_Enable(uint8_t Counter);
92 |
93 | /* Interrupts and flags management functions **********************************/
94 | FlagStatus WWDG_GetFlagStatus(void);
95 | void WWDG_ClearFlag(void);
96 |
97 | #ifdef __cplusplus
98 | }
99 | #endif
100 |
101 | #endif /* __STM32F4xx_WWDG_H */
102 |
103 | /**
104 | * @}
105 | */
106 |
107 | /**
108 | * @}
109 | */
110 |
111 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
112 |
--------------------------------------------------------------------------------
/src/data.h:
--------------------------------------------------------------------------------
1 | // Copyright 2025 Lukas Hrazky
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #pragma once
19 |
20 | #include "alert_tracker.h"
21 | #include "atr.h"
22 | #include "bms.h"
23 | #include "booster.h"
24 | #include "brake_tilt.h"
25 | #include "charging.h"
26 | #include "data_record.h"
27 | #include "footpad_sensor.h"
28 | #include "haptic_feedback.h"
29 | #include "imu.h"
30 | #include "konami.h"
31 | #include "lcm.h"
32 | #include "leds.h"
33 | #include "motor_control.h"
34 | #include "motor_data.h"
35 | #include "pid.h"
36 | #include "remote.h"
37 | #include "state.h"
38 | #include "time.h"
39 | #include "torque_tilt.h"
40 | #include "turn_tilt.h"
41 |
42 | #include
43 |
44 | typedef struct {
45 | lib_thread main_thread;
46 | lib_thread aux_thread;
47 |
48 | RefloatConfig float_conf;
49 |
50 | // Firmware version, passed in from Lisp
51 | int fw_version_major, fw_version_minor, fw_version_beta;
52 |
53 | // IMU data for the balancing filter
54 | BalanceFilterData balance_filter;
55 |
56 | Time time;
57 | MotorData motor;
58 | IMU imu;
59 | PID pid;
60 | MotorControl motor_control;
61 |
62 | TorqueTilt torque_tilt;
63 | ATR atr;
64 | BrakeTilt brake_tilt;
65 | TurnTilt turn_tilt;
66 | Booster booster;
67 | Remote remote;
68 |
69 | State state;
70 | FootpadSensor footpad;
71 | HapticFeedback haptic_feedback;
72 | AlertTracker alert_tracker;
73 |
74 | Leds leds;
75 | LcmData lcm;
76 | Charging charging;
77 | BMS bms;
78 |
79 | DataRecord data_record;
80 |
81 | Konami flywheel_konami;
82 | Konami headlights_on_konami;
83 | Konami headlights_off_konami;
84 |
85 | // Beeper
86 | int beep_num_left;
87 | int beep_duration;
88 | int beep_countdown;
89 | int beep_reason;
90 | bool beeper_enabled;
91 |
92 | // Config values
93 | uint32_t loop_time_us;
94 | float startup_pitch_trickmargin, startup_pitch_tolerance;
95 | float startup_step_size;
96 | float tiltback_duty_step_size, tiltback_hv_step_size, tiltback_lv_step_size,
97 | tiltback_return_step_size;
98 | float tiltback_variable, tiltback_variable_max_erpm, noseangling_step_size;
99 | bool duty_beeping;
100 |
101 | float balance_current;
102 |
103 | float setpoint, setpoint_target, setpoint_target_interpolated;
104 | float noseangling_interpolated;
105 | time_t alert_timer;
106 | time_t nag_timer;
107 | float idle_voltage;
108 | time_t fault_angle_pitch_timer, fault_angle_roll_timer, fault_switch_timer,
109 | fault_switch_half_timer;
110 | time_t wheelslip_timer, tb_highvoltage_timer;
111 | float switch_warn_beep_erpm;
112 | bool traction_control;
113 |
114 | // Darkride aka upside down mode:
115 | bool is_upside_down_started; // dark ride has been engaged
116 | bool enable_upside_down; // dark ride mode is enabled (10 seconds after fault)
117 | time_t upside_down_fault_timer;
118 |
119 | // Feature: Flywheel
120 | bool flywheel_abort;
121 |
122 | // Feature: Reverse Stop
123 | float reverse_stop_step_size, reverse_tolerance, reverse_total_erpm;
124 | time_t reverse_timer;
125 |
126 | // Feature: Soft Start
127 | float softstart_pid_limit, softstart_ramp_step_size;
128 |
129 | uint64_t odometer;
130 |
131 | // Feature: RC Move (control via app while idle)
132 | int rc_steps;
133 | int rc_counter;
134 | float rc_current_target;
135 | float rc_current;
136 | } Data;
137 |
--------------------------------------------------------------------------------
/vesc_pkg_lib/stdperiph_stm32f4/CMSIS/ST/system_stm32f4xx.h:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * @file system_stm32f4xx.h
4 | * @author MCD Application Team
5 | * @version V2.1.0
6 | * @date 19-June-2014
7 | * @brief CMSIS Cortex-M4 Device System Source File for STM32F4xx devices.
8 | ******************************************************************************
9 | * @attention
10 | *
11 | * © COPYRIGHT(c) 2014 STMicroelectronics
12 | *
13 | * Redistribution and use in source and binary forms, with or without modification,
14 | * are permitted provided that the following conditions are met:
15 | * 1. Redistributions of source code must retain the above copyright notice,
16 | * this list of conditions and the following disclaimer.
17 | * 2. Redistributions in binary form must reproduce the above copyright notice,
18 | * this list of conditions and the following disclaimer in the documentation
19 | * and/or other materials provided with the distribution.
20 | * 3. Neither the name of STMicroelectronics nor the names of its contributors
21 | * may be used to endorse or promote products derived from this software
22 | * without specific prior written permission.
23 | *
24 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
25 | * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
26 | * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
27 | * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
28 | * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
29 | * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
30 | * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
32 | * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
33 | * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
34 | *
35 | ******************************************************************************
36 | */
37 |
38 | /** @addtogroup CMSIS
39 | * @{
40 | */
41 |
42 | /** @addtogroup stm32f4xx_system
43 | * @{
44 | */
45 |
46 | /**
47 | * @brief Define to prevent recursive inclusion
48 | */
49 | #ifndef __SYSTEM_STM32F4XX_H
50 | #define __SYSTEM_STM32F4XX_H
51 |
52 | #ifdef __cplusplus
53 | extern "C" {
54 | #endif
55 |
56 | /** @addtogroup STM32F4xx_System_Includes
57 | * @{
58 | */
59 |
60 | /**
61 | * @}
62 | */
63 |
64 |
65 | /** @addtogroup STM32F4xx_System_Exported_types
66 | * @{
67 | */
68 | /* This variable is updated in three ways:
69 | 1) by calling CMSIS function SystemCoreClockUpdate()
70 | 2) by calling HAL API function HAL_RCC_GetSysClockFreq()
71 | 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency
72 | Note: If you use this function to configure the system clock; then there
73 | is no need to call the 2 first functions listed above, since SystemCoreClock
74 | variable is updated automatically.
75 | */
76 | extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
77 |
78 |
79 | /**
80 | * @}
81 | */
82 |
83 | /** @addtogroup STM32F4xx_System_Exported_Constants
84 | * @{
85 | */
86 |
87 | /**
88 | * @}
89 | */
90 |
91 | /** @addtogroup STM32F4xx_System_Exported_Macros
92 | * @{
93 | */
94 |
95 | /**
96 | * @}
97 | */
98 |
99 | /** @addtogroup STM32F4xx_System_Exported_Functions
100 | * @{
101 | */
102 |
103 | extern void SystemInit(void);
104 | extern void SystemCoreClockUpdate(void);
105 | /**
106 | * @}
107 | */
108 |
109 | #ifdef __cplusplus
110 | }
111 | #endif
112 |
113 | #endif /*__SYSTEM_STM32F4XX_H */
114 |
115 | /**
116 | * @}
117 | */
118 |
119 | /**
120 | * @}
121 | */
122 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
123 |
--------------------------------------------------------------------------------
/CONTRIBUTING.md:
--------------------------------------------------------------------------------
1 | # Contributing
2 | Bugfix Pull Requests are always welcome. If you want to implement a feature, it is advised get in touch first, to make sure your feature is in line with the direction Refloat development is heading.
3 |
4 | ## Commit Messages
5 | Use descriptive (but succint) commit title. For non-trivial commits, add a short commit description with any due explanation.
6 |
7 | If the commit fixes a bug or adds a feature that should be mentioned in the changelog, add a `Fix:` or `Feature:` [git trailer](https://alchemists.io/articles/git_trailers) respectively.
8 |
9 | Note the trailers need to go at the end of the commit description and be preceded by an empty line.
10 |
11 | A limitation of trailers is they don't support formatted multiline content. A workaround is in place for this, use this format for multiline changelog records:
12 |
13 | ```
14 | commit 1a5b1e0950df424eb9a7876ea2af57f3f652922f
15 | Author: Lukáš Hrázký
16 | Date: Sun Sep 17 13:35:16 2023 +0200
17 |
18 | Swap the firmware internal imu filter and the true pitch filter
19 |
20 | Use the firmware internal filter as the "true pitch" filter, with a
21 | "standard" Mahony setup. Change the Float package "true pitch" filter to
22 | act as the main balancing filter with the special Mahony kp ~= 2.
23 |
24 | Feature: Separate Mahony KP configuration between package and firmware
25 | >
26 | Mahony KP configuration is now separate between the App Config
27 | (firmware) and the Refloat Config (package). The App Config KP is now
28 | used for "true pitch", meaning a standard KP of less than 1 is
29 | required. (Float used Mahony KP of 0.2, here 0.4 is used, as it seems
30 | to work better)
31 | >
32 | To make the transition seamless and to ensure no misconfiguration
33 | happens, Refloat will set the following values in App Config -> IMU if
34 | it detects Mahony KP greater than 1 being configured there:
35 | >
36 | - Mahony KP: 0.4
37 | >
38 | - Mahony KI: 0
39 | >
40 | - Accelerometer Confidence Decay: 0.1
41 | >
42 | You don't need to do anything when transitioning from Float package,
43 | but you can check the values are as described after installation.
44 | >
45 | A new Refloat Config item Accelerometer Confidence Decay has been
46 | added to the package, which is used for the Refloat balance filter.
47 | ```
48 |
49 | That is, use `>` as a new line marker and indent all lines with a single space.
50 |
51 | The `changelog.py` script is used to generate the final changelog (it's not perfect, sometimes minor hand-tuning is needed), you can try to run it to see if your trailer works properly. It processes commits in history until it encounters the first version tag (excluding the HEAD commit even if it is tagged).
52 |
53 | ## Pull Requests (PRs)
54 | - Each commit should be a single independent change, be functional by itself and not contain unrelated changes.
55 | - Use _rebase workflow_ for all PRs.
56 | - When addressing review comments, if possible, update original commits with fixes belonging to them. Then force-push.
57 |
58 | ## CI
59 | CI runs on every push to main and needs to pass on every PR. It:
60 | - Runs a build of the package.
61 | - Checks formatting of C sources using `clang-format`.
62 |
63 | ## Code Formatting
64 | C code is automatically formatted using `clang-format` version 18 (you need to provide this dependency yourself).
65 |
66 | The rest of the code (namely, the QML AppUI sources) is not auto-formatted. Please do your best to adhere to formatting you see surrounding the code you're editing.
67 |
68 | You can format C source files via `clang-format` directly e.g. like this (non-recursive):
69 | ```sh
70 | clang-format -i src/*.{h,c}
71 | ```
72 |
73 | But, it's better to use git hooks.
74 |
75 | ## Git Hooks
76 | Refloat uses `pre-commit` for managing git hooks. Again, you need to install this dependency in your development environment. Then run this to install the commit hook in the repo:
77 | ```sh
78 | pre-commit install
79 | ```
80 |
81 | After this, `pre-commit` will automatically run clang-format on every commit you make, check and automatically fix your formatting.
82 |
83 | ## Naming Conventions
84 | - Type names are in `PascalCase`.
85 | - Global constants and enum items are in `SCREAMING_CASE`.
86 | - Variables (local, global, struct members) and functions are in `snake_case`.
87 | - File names are in `snake_case.c`.
88 |
--------------------------------------------------------------------------------
/vesc_pkg_lib/stdperiph_stm32f4/inc/stm32f4_gpio_af.h:
--------------------------------------------------------------------------------
1 |
2 | #ifndef _STM32F4_GPIO_AF_H_
3 | #define _STM32F4_GPIO_AF_H_
4 |
5 | /**
6 | * @brief AF 0 selection
7 | */
8 | #define GPIO_AF_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */
9 | #define GPIO_AF_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */
10 | #define GPIO_AF_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */
11 | #define GPIO_AF_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */
12 | #define GPIO_AF_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */
13 |
14 | /**
15 | * @brief AF 1 selection
16 | */
17 | #define GPIO_AF_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */
18 | #define GPIO_AF_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */
19 |
20 | /**
21 | * @brief AF 2 selection
22 | */
23 | #define GPIO_AF_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */
24 | #define GPIO_AF_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */
25 | #define GPIO_AF_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */
26 |
27 | /**
28 | * @brief AF 3 selection
29 | */
30 | #define GPIO_AF_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */
31 | #define GPIO_AF_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */
32 | #define GPIO_AF_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */
33 | #define GPIO_AF_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */
34 |
35 | /**
36 | * @brief AF 4 selection
37 | */
38 | #define GPIO_AF_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */
39 | #define GPIO_AF_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */
40 | #define GPIO_AF_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */
41 |
42 | /**
43 | * @brief AF 5 selection
44 | */
45 | #define GPIO_AF_SPI1 ((uint8_t)0x05) /* SPI1 Alternate Function mapping */
46 | #define GPIO_AF_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */
47 |
48 | /**
49 | * @brief AF 6 selection
50 | */
51 | #define GPIO_AF_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */
52 |
53 | /**
54 | * @brief AF 7 selection
55 | */
56 | #define GPIO_AF_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */
57 | #define GPIO_AF_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */
58 | #define GPIO_AF_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */
59 | #define GPIO_AF_I2S3ext ((uint8_t)0x07) /* I2S3ext Alternate Function mapping */
60 |
61 | /**
62 | * @brief AF 8 selection
63 | */
64 | #define GPIO_AF_UART4 ((uint8_t)0x08) /* UART4 Alternate Function mapping */
65 | #define GPIO_AF_UART5 ((uint8_t)0x08) /* UART5 Alternate Function mapping */
66 | #define GPIO_AF_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */
67 |
68 | /**
69 | * @brief AF 9 selection
70 | */
71 | #define GPIO_AF_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */
72 | #define GPIO_AF_CAN2 ((uint8_t)0x09) /* CAN2 Alternate Function mapping */
73 | #define GPIO_AF_TIM12 ((uint8_t)0x09) /* TIM12 Alternate Function mapping */
74 | #define GPIO_AF_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */
75 | #define GPIO_AF_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */
76 |
77 | /**
78 | * @brief AF 10 selection
79 | */
80 | #define GPIO_AF_OTG_FS ((uint8_t)0xA) /* OTG_FS Alternate Function mapping */
81 | #define GPIO_AF_OTG_HS ((uint8_t)0xA) /* OTG_HS Alternate Function mapping */
82 |
83 | /**
84 | * @brief AF 11 selection
85 | */
86 | #define GPIO_AF_ETH ((uint8_t)0x0B) /* ETHERNET Alternate Function mapping */
87 |
88 | /**
89 | * @brief AF 12 selection
90 | */
91 | #define GPIO_AF_FSMC ((uint8_t)0xC) /* FSMC Alternate Function mapping */
92 | #define GPIO_AF_OTG_HS_FS ((uint8_t)0xC) /* OTG HS configured in FS, Alternate Function mapping */
93 | #define GPIO_AF_SDIO ((uint8_t)0xC) /* SDIO Alternate Function mapping */
94 |
95 | /**
96 | * @brief AF 13 selection
97 | */
98 | #define GPIO_AF_DCMI ((uint8_t)0x0D) /* DCMI Alternate Function mapping */
99 |
100 | /**
101 | * @brief AF 15 selection
102 | */
103 | #define GPIO_AF_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */
104 |
105 | #endif
106 |
107 |
--------------------------------------------------------------------------------
/doc/commands/DATA_RECORD.md:
--------------------------------------------------------------------------------
1 | # Command: DATA_RECORD
2 |
3 | This command is compound, it has one request message and two response messages.
4 |
5 | It serves for controlling the data recording capability of the package. See [Realtime Value Tracking](../realtime_value_tracking.md) for more details.
6 |
7 | ## DATA_RECORD_REQUEST (Request)
8 |
9 | **ID**: 41
10 |
11 | A single request command to control the data recording functionality.
12 |
13 | | Offset | Size | Name | Mandatory | Description |
14 | |--------|------|-----------|-----------|---------------|
15 | | 0 | 1 | `mode` | Yes | `1`: Control
`2`: Send
|
16 | | 1 | 1 | `sub_mode`| Yes | Submode is different for each of the two modes. |
17 |
18 | ### Mode: Control
19 |
20 | Control mode expects one additional parameter:
21 |
22 | | Offset | Size | Name | Mandatory | Description |
23 | |--------|------|---------|-----------|---------------|
24 | | 0 | 1 | `value` | Yes | Represents a boolean value to set for given `sub_mode`. |
25 |
26 | - **`sub_mode = 1`: Start/Stop Recording**
27 | `value = 1` starts recording, `value = 0` stops recording.
28 |
29 | - **`sub_mode = 2`: Set Autostart to `value`**.\
30 | _Autostart will automatically start recording when engaging the board. Default value: True_
31 |
32 | - **`sub_mode = 3`: Set Autostop to `value`**.\
33 | _Autostop will automatically stop recording when disengaged. Default value: True_
34 |
35 | ### Mode: Send
36 |
37 | Requests sending the data. Send mode has two submodes:
38 |
39 | - **`sub_mode = 1`: Send Header**
40 | - **`sub_mode = 2`: Send Data**
41 |
42 | The Send Header submode should be sent first to get the metadata, followed by a series of Send Data requests.
43 |
44 | #### Send Header
45 |
46 | This submode has no additional parameters and the package will respond with the `DATA_RECORD_HEADER` Response.
47 |
48 | _Note: Requesting the header will pause the recording. If the recording would continue while the data are being fetched, it would overwrite them as they are being read, there is no safeguard._
49 |
50 | #### Send Data
51 |
52 | This submode has one additional parameter:
53 |
54 | | Offset | Size | Name | Mandatory | Description |
55 | |--------|------|----------|-----------|---------------|
56 | | 0 | 4 | `offset` | Yes | Offset in number of samples to send. |
57 |
58 | The client is responsible to request all the chunks of data by repeatedly calling this command with the offsets of the data it needs to fetch.
59 |
60 | ## DATA_RECORD_HEADER (Response)
61 |
62 | **ID**: 42
63 |
64 | Response with the metadata for the recorded data. Sends the total number of samples and then a list of [string](string.md) IDs for the values in each sample, same as in [REALTIME_DATA](REALTIME_DATA.md).
65 |
66 | | Offset | Size | Name | Description |
67 | |--------|------|--------------------------|---------------|
68 | | 0 | 4 | `size` | Size of the buffer in number of samples. The client is expected to fetch up to this number of samples. |
69 | | 4 | 1 | `recorded_data_id_count` | Number of the recorded items per sample (sample size). |
70 | | 5 | ? | `recorded_data_ids` | A [string](string.md) sequence repeated `recorded_data_id_count` times. |
71 |
72 | ## DATA_RECORD_DATA (Response)
73 |
74 | **ID**: 43
75 |
76 | Response with the actual sample data at the `offset` given in the request.
77 |
78 | | Offset | Size | Name | Description |
79 | |--------|------|--------------------------|---------------|
80 | | 0 | 4 | `offset` | `offset` repeated in the response. |
81 | | 4 | ? | `samples` | An unspecified number of `sample`s follows until the end of the message. |
82 |
83 | **`sample`**:
84 | | Offset | Size | Name | Description |
85 | |--------|------|----------|---------------|
86 | | 0 | 4 | `time` | Timestamp of the sample in ticks, as `uint32`. |
87 | | 4 | 1 | `flags` | Important runtime flags and state. |
88 | | 5 | ? | `values` | A sequence of sample values, each 16 bits long and encoded in [float16](float16.md). The number of values is equal to the number of IDs sent in `DATA_RECORD_HEADER`. |
89 |
90 | #### flags
91 |
92 | | 7-4 | 3-2 | 1 | 0 |
93 | |-------|-----------------|-------------|-----------|
94 | | `sat` | `footpad_state` | `wheelslip` | `running` |
95 |
96 | **`footpad_state`**:
97 | - `0: NONE`
98 | - `1: LEFT`
99 | - `2: RIGHT`
100 | - `3: BOTH`
101 |
102 | **`sat` (setpoint adjustment type)**:
103 | - `0: NONE`
104 | - `1: CENTERING`
105 | - `2: REVERSESTOP`
106 | - `6: PB_DUTY`
107 | - `10: PB_HIGH_VOLTAGE`
108 | - `11: PB_LOW_VOLTAGE`
109 | - `12: PB_TEMPERATURE`
110 |
--------------------------------------------------------------------------------
/vesc_pkg_lib/stdperiph_stm32f4/inc/stm32f4xx_iwdg.h:
--------------------------------------------------------------------------------
1 | /**
2 | ******************************************************************************
3 | * @file stm32f4xx_iwdg.h
4 | * @author MCD Application Team
5 | * @version V1.6.0
6 | * @date 10-July-2015
7 | * @brief This file contains all the functions prototypes for the IWDG
8 | * firmware library.
9 | ******************************************************************************
10 | * @attention
11 | *
12 | * © COPYRIGHT 2015 STMicroelectronics
13 | *
14 | * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
15 | * You may not use this file except in compliance with the License.
16 | * You may obtain a copy of the License at:
17 | *
18 | * http://www.st.com/software_license_agreement_liberty_v2
19 | *
20 | * Unless required by applicable law or agreed to in writing, software
21 | * distributed under the License is distributed on an "AS IS" BASIS,
22 | * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
23 | * See the License for the specific language governing permissions and
24 | * limitations under the License.
25 | *
26 | ******************************************************************************
27 | */
28 |
29 | /* Define to prevent recursive inclusion -------------------------------------*/
30 | #ifndef __STM32F4xx_IWDG_H
31 | #define __STM32F4xx_IWDG_H
32 |
33 | #ifdef __cplusplus
34 | extern "C" {
35 | #endif
36 |
37 | /* Includes ------------------------------------------------------------------*/
38 | #include "stm32f4xx.h"
39 |
40 | /** @addtogroup STM32F4xx_StdPeriph_Driver
41 | * @{
42 | */
43 |
44 | /** @addtogroup IWDG
45 | * @{
46 | */
47 |
48 | /* Exported types ------------------------------------------------------------*/
49 | /* Exported constants --------------------------------------------------------*/
50 |
51 | /** @defgroup IWDG_Exported_Constants
52 | * @{
53 | */
54 |
55 | /** @defgroup IWDG_WriteAccess
56 | * @{
57 | */
58 | #define IWDG_WriteAccess_Enable ((uint16_t)0x5555)
59 | #define IWDG_WriteAccess_Disable ((uint16_t)0x0000)
60 | #define IS_IWDG_WRITE_ACCESS(ACCESS) (((ACCESS) == IWDG_WriteAccess_Enable) || \
61 | ((ACCESS) == IWDG_WriteAccess_Disable))
62 | /**
63 | * @}
64 | */
65 |
66 | /** @defgroup IWDG_prescaler
67 | * @{
68 | */
69 | #define IWDG_Prescaler_4 ((uint8_t)0x00)
70 | #define IWDG_Prescaler_8 ((uint8_t)0x01)
71 | #define IWDG_Prescaler_16 ((uint8_t)0x02)
72 | #define IWDG_Prescaler_32 ((uint8_t)0x03)
73 | #define IWDG_Prescaler_64 ((uint8_t)0x04)
74 | #define IWDG_Prescaler_128 ((uint8_t)0x05)
75 | #define IWDG_Prescaler_256 ((uint8_t)0x06)
76 | #define IS_IWDG_PRESCALER(PRESCALER) (((PRESCALER) == IWDG_Prescaler_4) || \
77 | ((PRESCALER) == IWDG_Prescaler_8) || \
78 | ((PRESCALER) == IWDG_Prescaler_16) || \
79 | ((PRESCALER) == IWDG_Prescaler_32) || \
80 | ((PRESCALER) == IWDG_Prescaler_64) || \
81 | ((PRESCALER) == IWDG_Prescaler_128)|| \
82 | ((PRESCALER) == IWDG_Prescaler_256))
83 | /**
84 | * @}
85 | */
86 |
87 | /** @defgroup IWDG_Flag
88 | * @{
89 | */
90 | #define IWDG_FLAG_PVU ((uint16_t)0x0001)
91 | #define IWDG_FLAG_RVU ((uint16_t)0x0002)
92 | #define IS_IWDG_FLAG(FLAG) (((FLAG) == IWDG_FLAG_PVU) || ((FLAG) == IWDG_FLAG_RVU))
93 | #define IS_IWDG_RELOAD(RELOAD) ((RELOAD) <= 0xFFF)
94 | /**
95 | * @}
96 | */
97 |
98 | /**
99 | * @}
100 | */
101 |
102 | /* Exported macro ------------------------------------------------------------*/
103 | /* Exported functions --------------------------------------------------------*/
104 |
105 | /* Prescaler and Counter configuration functions ******************************/
106 | void IWDG_WriteAccessCmd(uint16_t IWDG_WriteAccess);
107 | void IWDG_SetPrescaler(uint8_t IWDG_Prescaler);
108 | void IWDG_SetReload(uint16_t Reload);
109 | void IWDG_ReloadCounter(void);
110 |
111 | /* IWDG activation function ***************************************************/
112 | void IWDG_Enable(void);
113 |
114 | /* Flag management function ***************************************************/
115 | FlagStatus IWDG_GetFlagStatus(uint16_t IWDG_FLAG);
116 |
117 | #ifdef __cplusplus
118 | }
119 | #endif
120 |
121 | #endif /* __STM32F4xx_IWDG_H */
122 |
123 | /**
124 | * @}
125 | */
126 |
127 | /**
128 | * @}
129 | */
130 |
131 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
132 |
--------------------------------------------------------------------------------
/src/turn_tilt.c:
--------------------------------------------------------------------------------
1 | // Copyright 2025 Lukas Hrazky
2 | //
3 | // This file is part of the Refloat VESC package.
4 | //
5 | // Refloat VESC package is free software: you can redistribute it and/or modify
6 | // it under the terms of the GNU General Public License as published by the
7 | // Free Software Foundation, either version 3 of the License, or (at your
8 | // option) any later version.
9 | //
10 | // Refloat VESC package is distributed in the hope that it will be useful, but
11 | // WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
12 | // or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
13 | // more details.
14 | //
15 | // You should have received a copy of the GNU General Public License along with
16 | // this program. If not, see .
17 |
18 | #include "turn_tilt.h"
19 |
20 | #include "utils.h"
21 |
22 | #include
23 |
24 | void turn_tilt_init(TurnTilt *tt) {
25 | tt->step_size = 0.0f;
26 | tt->boost_per_erpm = 0.0f;
27 | turn_tilt_reset(tt);
28 | }
29 |
30 | void turn_tilt_reset(TurnTilt *tt) {
31 | tt->last_yaw_angle = 0.0f;
32 | tt->last_yaw_change = 0.0f;
33 | tt->yaw_change = 0.0f;
34 | tt->abs_yaw_change = 0.0f;
35 | tt->yaw_aggregate = 0.0f;
36 |
37 | tt->ramped_step_size = 0.0f;
38 | tt->target = 0.0f;
39 | tt->setpoint = 0.0f;
40 | }
41 |
42 | void turn_tilt_configure(TurnTilt *tt, const RefloatConfig *config) {
43 | tt->step_size = config->turntilt_speed / config->hertz;
44 | tt->boost_per_erpm =
45 | (float) config->turntilt_erpm_boost / 100.0 / config->turntilt_erpm_boost_end;
46 | }
47 |
48 | void turn_tilt_aggregate(TurnTilt *tt, const IMU *imu) {
49 | float new_change = imu->yaw - tt->last_yaw_angle;
50 | bool unchanged = false;
51 |
52 | // exact 0's only happen when the IMU is not updating between loops,
53 | // yaw flips signs at 180, ignore those changes
54 | if (new_change == 0 || fabsf(new_change) > 100) {
55 | new_change = tt->last_yaw_change;
56 | unchanged = true;
57 | }
58 | tt->last_yaw_change = new_change;
59 | tt->last_yaw_angle = imu->yaw;
60 |
61 | // limit change to avoid overreactions at low speed
62 | tt->yaw_change = 0.8 * tt->yaw_change + 0.2 * clampf(new_change, -0.10, 0.10);
63 |
64 | // clear the aggregate yaw whenever we change direction
65 | if (sign(tt->yaw_change) != sign(tt->yaw_aggregate)) {
66 | tt->yaw_aggregate = 0;
67 | }
68 |
69 | tt->abs_yaw_change = fabsf(tt->yaw_change);
70 | // don't count tiny yaw changes towards aggregate
71 | if (tt->abs_yaw_change > 0.04 && !unchanged) {
72 | tt->yaw_aggregate += tt->yaw_change;
73 | }
74 | }
75 |
76 | void turn_tilt_update(TurnTilt *tt, const MotorData *md, const RefloatConfig *config) {
77 | if (config->turntilt_strength == 0) {
78 | return;
79 | }
80 |
81 | float abs_yaw_aggregate = fabsf(tt->yaw_aggregate);
82 |
83 | // Minimum threshold based on
84 | // a) minimum degrees per second (yaw/turn increment)
85 | // b) minimum yaw aggregate (to filter out wiggling on uneven road)
86 | if (abs_yaw_aggregate < config->turntilt_start_angle || tt->abs_yaw_change < 0.04) {
87 | tt->target = 0;
88 | } else {
89 | // Calculate desired angle
90 | tt->target = tt->abs_yaw_change * config->turntilt_strength;
91 |
92 | // Apply speed scaling
93 | float boost;
94 | if (md->abs_erpm < config->turntilt_erpm_boost_end) {
95 | boost = 1.0 + md->abs_erpm * tt->boost_per_erpm;
96 | } else {
97 | boost = 1.0 + (float) config->turntilt_erpm_boost / 100.0;
98 | }
99 | tt->target *= boost;
100 |
101 | // Increase turntilt based on aggregate yaw change (at most: double it)
102 | float aggregate_damper = 1.0;
103 | if (md->abs_erpm < 2000) {
104 | aggregate_damper = 0.5;
105 | }
106 | boost = 1 + aggregate_damper * abs_yaw_aggregate / config->turntilt_yaw_aggregate;
107 | boost = fminf(boost, 2);
108 | tt->target *= boost;
109 |
110 | // Limit angle to max angle
111 | if (tt->target > 0) {
112 | tt->target = fminf(tt->target, config->turntilt_angle_limit);
113 | } else {
114 | tt->target = fmaxf(tt->target, -config->turntilt_angle_limit);
115 | }
116 |
117 | // Disable below erpm threshold otherwise add directionality
118 | if (md->abs_erpm < config->turntilt_start_erpm) {
119 | tt->target = 0;
120 | } else {
121 | tt->target *= md->erpm_sign;
122 | }
123 | }
124 |
125 | // Smoothen changes in tilt angle by ramping the step size
126 | smooth_rampf(&tt->setpoint, &tt->ramped_step_size, tt->target, tt->step_size, 0.04, 1.5);
127 | }
128 |
129 | void turn_tilt_winddown(TurnTilt *tt) {
130 | tt->setpoint *= 0.995;
131 | }
132 |
--------------------------------------------------------------------------------