├── .github ├── ISSUE_TEMPLATE │ ├── bug_report.md │ └── feature_request.md ├── actions │ ├── add-version-to-channel │ │ └── action.yml │ └── upload-release │ │ ├── action.yml │ │ └── private_release_api.py └── workflows │ ├── documentation.yml │ └── firmware.yaml ├── .gitignore ├── Arduino ├── ArduinoI2C │ ├── ArduinoI2C.ino │ ├── odrive.h │ ├── odrive_endpoints.h │ └── type_traits.h └── ODriveArduino │ ├── LICENSE │ ├── ODriveArduino.cpp │ ├── ODriveArduino.h │ ├── ODriveEnums.h │ ├── README.md │ └── examples │ └── ODriveArduinoTest │ └── ODriveArduinoTest.ino ├── CHANGELOG.md ├── Dockerfile ├── Firmware ├── .clang-format ├── .gitignore ├── .vscode │ ├── c_cpp_properties.json │ ├── launch.json │ ├── settings.json │ └── tasks.json ├── Board │ └── v3 │ │ ├── Inc │ │ ├── FreeRTOSConfig.h │ │ ├── adc.h │ │ ├── board.h │ │ ├── can.h │ │ ├── dma.h │ │ ├── gpio.h │ │ ├── i2c.h │ │ ├── main.h │ │ ├── mxconstants.h │ │ ├── prev_board_ver │ │ │ ├── main_V3_2.h │ │ │ └── main_V3_4.h │ │ ├── spi.h │ │ ├── stm32f4xx_hal_conf.h │ │ ├── stm32f4xx_it.h │ │ ├── tim.h │ │ ├── usart.h │ │ ├── usb_device.h │ │ ├── usbd_cdc_if.h │ │ ├── usbd_conf.h │ │ └── usbd_desc.h │ │ ├── Makefile │ │ ├── Odrive.ioc │ │ ├── STM32F405RGTx_FLASH.ld │ │ ├── STM32F40x.svd │ │ ├── Src │ │ ├── adc.c │ │ ├── can.c │ │ ├── dma.c │ │ ├── freertos.c │ │ ├── gpio.c │ │ ├── i2c.c │ │ ├── main.c │ │ ├── prev_board_ver │ │ │ ├── adc_V3_2.c │ │ │ ├── adc_V3_4.c │ │ │ ├── gpio_V3_2.c │ │ │ └── gpio_V3_4.c │ │ ├── spi.c │ │ ├── stm32f4xx_hal_msp.c │ │ ├── stm32f4xx_hal_timebase_TIM.c │ │ ├── stm32f4xx_it.c │ │ ├── system_stm32f4xx.c │ │ ├── tim.c │ │ ├── usart.c │ │ ├── usb_device.c │ │ ├── usbd_cdc_if.c │ │ ├── usbd_conf.c │ │ └── usbd_desc.c │ │ ├── board.cpp │ │ └── startup_stm32f405xx.s ├── Drivers │ ├── DRV8301 │ │ ├── drv8301.cpp │ │ └── drv8301.hpp │ ├── STM32 │ │ ├── stm32_gpio.cpp │ │ ├── stm32_gpio.hpp │ │ ├── stm32_nvm.c │ │ ├── stm32_nvm.h │ │ ├── stm32_spi_arbiter.cpp │ │ ├── stm32_spi_arbiter.hpp │ │ ├── stm32_system.cpp │ │ ├── stm32_system.h │ │ └── stm32_timer.hpp │ └── gate_driver.hpp ├── FreeRTOS-openocd.c ├── LICENSE ├── Makefile ├── MotorControl │ ├── acim_estimator.cpp │ ├── acim_estimator.hpp │ ├── arm_cos_f32.c │ ├── arm_sin_f32.c │ ├── axis.cpp │ ├── axis.hpp │ ├── component.hpp │ ├── controller.cpp │ ├── controller.hpp │ ├── current_limiter.hpp │ ├── encoder.cpp │ ├── encoder.hpp │ ├── endstop.cpp │ ├── endstop.hpp │ ├── example.json │ ├── foc.cpp │ ├── foc.hpp │ ├── low_level.cpp │ ├── low_level.h │ ├── main.cpp │ ├── mechanical_brake.cpp │ ├── mechanical_brake.hpp │ ├── motor.cpp │ ├── motor.hpp │ ├── nvm_config.hpp │ ├── odrive_main.h │ ├── open_loop_controller.cpp │ ├── open_loop_controller.hpp │ ├── oscilloscope.cpp │ ├── oscilloscope.hpp │ ├── phase_control_law.hpp │ ├── pwm_input.cpp │ ├── pwm_input.hpp │ ├── sensorless_estimator.cpp │ ├── sensorless_estimator.hpp │ ├── task_timer.hpp │ ├── thermistor.cpp │ ├── thermistor.hpp │ ├── timer.hpp │ ├── trapTraj.cpp │ ├── trapTraj.hpp │ ├── utils.cpp │ └── utils.hpp ├── ODriveFirmware.launch ├── Tests │ ├── test_can.cpp │ ├── test_rotate.cpp │ ├── test_runner.cpp │ ├── test_timer.cpp │ └── test_trap_traj.cpp ├── ThirdParty │ ├── CMSIS │ │ ├── Device │ │ │ └── ST │ │ │ │ ├── STM32F4xx │ │ │ │ └── Include │ │ │ │ │ ├── stm32f405xx.h │ │ │ │ │ ├── stm32f4xx.h │ │ │ │ │ └── system_stm32f4xx.h │ │ │ │ └── STM32F7xx │ │ │ │ └── Include │ │ │ │ ├── stm32f722xx.h │ │ │ │ ├── stm32f7xx.h │ │ │ │ └── system_stm32f7xx.h │ │ ├── Include │ │ │ ├── arm_common_tables.h │ │ │ ├── arm_const_structs.h │ │ │ ├── arm_math.h │ │ │ ├── cmsis_armcc.h │ │ │ ├── cmsis_armclang.h │ │ │ ├── cmsis_compiler.h │ │ │ ├── cmsis_gcc.h │ │ │ ├── cmsis_iccarm.h │ │ │ ├── cmsis_version.h │ │ │ ├── core_armv8mbl.h │ │ │ ├── core_armv8mml.h │ │ │ ├── core_cm0.h │ │ │ ├── core_cm0plus.h │ │ │ ├── core_cm1.h │ │ │ ├── core_cm23.h │ │ │ ├── core_cm3.h │ │ │ ├── core_cm33.h │ │ │ ├── core_cm4.h │ │ │ ├── core_cm7.h │ │ │ ├── core_sc000.h │ │ │ ├── core_sc300.h │ │ │ ├── mpu_armv7.h │ │ │ ├── mpu_armv8.h │ │ │ └── tz_context.h │ │ └── Lib │ │ │ └── GCC │ │ │ ├── libarm_cortexM4lf_math.a │ │ │ └── libarm_cortexM7lfsp_math.a │ ├── FreeRTOS │ │ └── Source │ │ │ ├── CMSIS_RTOS │ │ │ ├── cmsis_os.c │ │ │ └── cmsis_os.h │ │ │ ├── croutine.c │ │ │ ├── event_groups.c │ │ │ ├── include │ │ │ ├── FreeRTOS.h │ │ │ ├── StackMacros.h │ │ │ ├── croutine.h │ │ │ ├── deprecated_definitions.h │ │ │ ├── event_groups.h │ │ │ ├── list.h │ │ │ ├── message_buffer.h │ │ │ ├── mpu_prototypes.h │ │ │ ├── mpu_wrappers.h │ │ │ ├── portable.h │ │ │ ├── projdefs.h │ │ │ ├── queue.h │ │ │ ├── semphr.h │ │ │ ├── stack_macros.h │ │ │ ├── stream_buffer.h │ │ │ ├── task.h │ │ │ └── timers.h │ │ │ ├── list.c │ │ │ ├── portable │ │ │ ├── GCC │ │ │ │ ├── ARM_CM4F │ │ │ │ │ ├── port.c │ │ │ │ │ └── portmacro.h │ │ │ │ └── ARM_CM7 │ │ │ │ │ └── r0p1 │ │ │ │ │ ├── port.c │ │ │ │ │ └── portmacro.h │ │ │ └── MemMang │ │ │ │ └── heap_4.c │ │ │ ├── queue.c │ │ │ ├── stream_buffer.c │ │ │ ├── tasks.c │ │ │ └── timers.c │ ├── STM32F4xx_HAL_Driver │ │ ├── Inc │ │ │ ├── Legacy │ │ │ │ └── stm32_hal_legacy.h │ │ │ ├── stm32f4xx_hal.h │ │ │ ├── stm32f4xx_hal_adc.h │ │ │ ├── stm32f4xx_hal_adc_ex.h │ │ │ ├── stm32f4xx_hal_can.h │ │ │ ├── stm32f4xx_hal_cortex.h │ │ │ ├── stm32f4xx_hal_def.h │ │ │ ├── stm32f4xx_hal_dma.h │ │ │ ├── stm32f4xx_hal_dma_ex.h │ │ │ ├── stm32f4xx_hal_flash.h │ │ │ ├── stm32f4xx_hal_flash_ex.h │ │ │ ├── stm32f4xx_hal_flash_ramfunc.h │ │ │ ├── stm32f4xx_hal_gpio.h │ │ │ ├── stm32f4xx_hal_gpio_ex.h │ │ │ ├── stm32f4xx_hal_i2c.h │ │ │ ├── stm32f4xx_hal_i2c_ex.h │ │ │ ├── stm32f4xx_hal_pcd.h │ │ │ ├── stm32f4xx_hal_pcd_ex.h │ │ │ ├── stm32f4xx_hal_pwr.h │ │ │ ├── stm32f4xx_hal_pwr_ex.h │ │ │ ├── stm32f4xx_hal_rcc.h │ │ │ ├── stm32f4xx_hal_rcc_ex.h │ │ │ ├── stm32f4xx_hal_spi.h │ │ │ ├── stm32f4xx_hal_tim.h │ │ │ ├── stm32f4xx_hal_tim_ex.h │ │ │ ├── stm32f4xx_hal_uart.h │ │ │ └── stm32f4xx_ll_usb.h │ │ └── Src │ │ │ ├── stm32f4xx_hal.c │ │ │ ├── stm32f4xx_hal_adc.c │ │ │ ├── stm32f4xx_hal_adc_ex.c │ │ │ ├── stm32f4xx_hal_can.c │ │ │ ├── stm32f4xx_hal_cortex.c │ │ │ ├── stm32f4xx_hal_dma.c │ │ │ ├── stm32f4xx_hal_dma_ex.c │ │ │ ├── stm32f4xx_hal_flash.c │ │ │ ├── stm32f4xx_hal_flash_ex.c │ │ │ ├── stm32f4xx_hal_flash_ramfunc.c │ │ │ ├── stm32f4xx_hal_gpio.c │ │ │ ├── stm32f4xx_hal_i2c.c │ │ │ ├── stm32f4xx_hal_i2c_ex.c │ │ │ ├── stm32f4xx_hal_pcd.c │ │ │ ├── stm32f4xx_hal_pcd_ex.c │ │ │ ├── stm32f4xx_hal_pwr.c │ │ │ ├── stm32f4xx_hal_pwr_ex.c │ │ │ ├── stm32f4xx_hal_rcc.c │ │ │ ├── stm32f4xx_hal_rcc_ex.c │ │ │ ├── stm32f4xx_hal_spi.c │ │ │ ├── stm32f4xx_hal_tim.c │ │ │ ├── stm32f4xx_hal_tim_ex.c │ │ │ ├── stm32f4xx_hal_uart.c │ │ │ └── stm32f4xx_ll_usb.c │ └── STM32_USB_Device_Library │ │ ├── Class │ │ └── CDC │ │ │ ├── Inc │ │ │ └── usbd_cdc.h │ │ │ └── Src │ │ │ └── usbd_cdc.c │ │ └── Core │ │ ├── Inc │ │ ├── usbd_core.h │ │ ├── usbd_ctlreq.h │ │ ├── usbd_def.h │ │ └── usbd_ioreq.h │ │ └── Src │ │ ├── usbd_core.c │ │ ├── usbd_ctlreq.c │ │ └── usbd_ioreq.c ├── Tupfile.ini ├── Tupfile.lua ├── Tuprules.lua ├── adctest.py ├── communication │ ├── ascii_protocol.cpp │ ├── ascii_protocol.hpp │ ├── can │ │ ├── can_helpers.hpp │ │ ├── can_simple.cpp │ │ ├── can_simple.hpp │ │ ├── canbus.hpp │ │ ├── odrive_can.cpp │ │ └── odrive_can.hpp │ ├── communication.cpp │ ├── communication.h │ ├── interface_can.hpp │ ├── interface_i2c.cpp │ ├── interface_i2c.h │ ├── interface_uart.cpp │ ├── interface_uart.h │ ├── interface_usb.cpp │ └── interface_usb.h ├── doctest │ ├── doctest.h │ └── parts │ │ ├── doctest.cpp │ │ └── doctest_fwd.h ├── fibre-cpp │ ├── .gitignore │ ├── Dockerfile │ ├── Makefile │ ├── README.md │ ├── Tupfile.lua │ ├── channel_discoverer.cpp │ ├── configs │ │ ├── linux-amd64.config │ │ ├── linux-armhf.config │ │ ├── macos-x86.config │ │ ├── wasm.config │ │ └── windows-amd64.config │ ├── crc.hpp │ ├── endpoints_template.j2 │ ├── fibre.cpp │ ├── function_stubs_template.j2 │ ├── get_dependencies.sh │ ├── include │ │ └── fibre │ │ │ ├── async_stream.hpp │ │ │ ├── bufptr.hpp │ │ │ ├── callback.hpp │ │ │ ├── channel_discoverer.hpp │ │ │ ├── cpp_utils.hpp │ │ │ ├── event_loop.hpp │ │ │ ├── fibre.hpp │ │ │ ├── introspection.hpp │ │ │ ├── libfibre.h │ │ │ ├── simple_serdes.hpp │ │ │ └── status.hpp │ ├── interfaces_template.j2 │ ├── legacy_object_client.cpp │ ├── legacy_object_client.hpp │ ├── legacy_protocol.cpp │ ├── legacy_protocol.hpp │ ├── libfibre.cpp │ ├── libfibre.version │ ├── logging.cpp │ ├── logging.hpp │ ├── package.lua │ ├── platform_support │ │ ├── epoll_event_loop.cpp │ │ ├── epoll_event_loop.hpp │ │ ├── libusb_transport.cpp │ │ ├── libusb_transport.hpp │ │ ├── posix_socket.cpp │ │ ├── posix_socket.hpp │ │ ├── posix_tcp_backend.cpp │ │ └── posix_tcp_backend.hpp │ ├── print_utils.hpp │ ├── protocol.hpp │ ├── stream_utils.hpp │ └── type_info_template.j2 ├── freertos_vars.h ├── interface_generator_stub.py ├── motor_timing.jpg ├── odrive-interface.yaml ├── sampler.py ├── syscalls.c ├── timing_diagram_v3.png └── tup.config.default ├── GUI ├── .gitignore ├── LICENSE.md ├── README.md ├── babel.config.js ├── fibre-js │ ├── README.md │ ├── example.gif │ ├── example.html │ ├── fibre.js │ ├── libfibre-wasm.js │ ├── libfibre-wasm.wasm │ ├── multidevice_example.html │ └── package.json ├── package-lock.json ├── package.json ├── public │ ├── favicon.ico │ ├── icon.png │ └── index.html ├── scripts │ └── enumGenerate.js ├── server │ └── odrive_server.py ├── src │ ├── App.vue │ ├── assets │ │ ├── dashboards │ │ │ ├── Tuning_0_4_12.json │ │ │ └── Tuning_0_5_1.json │ │ ├── images │ │ │ ├── 24v_300x300.png │ │ │ ├── 56v_300x300.png │ │ │ ├── D5065_300x300.png │ │ │ ├── D6374_300x300.png │ │ │ ├── M0M1_300x300.png │ │ │ ├── M0_300x300.png │ │ │ ├── M1_300x300.png │ │ │ ├── amt102-v_300x300.png │ │ │ ├── hall_effect_300x300.png │ │ │ └── temp.png │ │ ├── odrive-interface.yaml │ │ ├── odriveEnums.json │ │ ├── odrive_logo.png │ │ ├── styles │ │ │ ├── style.css │ │ │ └── vars.css │ │ └── wizard │ │ │ ├── configTemplate.json │ │ │ └── wizard.js │ ├── background.js │ ├── comms │ │ └── socketio.js │ ├── components │ │ ├── Axis.vue │ │ ├── actions │ │ │ ├── Action.vue │ │ │ └── ActionEnum.vue │ │ ├── clearErrors.vue │ │ ├── controls │ │ │ ├── CtrlBoolean.vue │ │ │ ├── CtrlEnum.vue │ │ │ ├── CtrlFunction.vue │ │ │ ├── CtrlNumeric.vue │ │ │ └── CtrlSlider.vue │ │ ├── plots │ │ │ ├── LineChart.js │ │ │ └── Plot.vue │ │ └── wizard │ │ │ ├── choices │ │ │ ├── wizardBrake.vue │ │ │ ├── wizardChoice.vue │ │ │ ├── wizardEncoderIncremental.vue │ │ │ ├── wizardEncoderIncrementalIndex.vue │ │ │ ├── wizardEnd.vue │ │ │ ├── wizardInputFiltered.vue │ │ │ ├── wizardInputTrajectory.vue │ │ │ ├── wizardInputVelRamp.vue │ │ │ ├── wizardMisc.vue │ │ │ └── wizardMotor.vue │ │ │ ├── page_components │ │ │ ├── wizardCalStatus.vue │ │ │ ├── wizardEncoderCal.vue │ │ │ └── wizardMotorCal.vue │ │ │ └── wizardPage.vue │ ├── lib │ │ ├── odrive_utils.js │ │ └── utils.js │ ├── main.js │ ├── preload.js │ ├── store.js │ └── views │ │ ├── Dashboard.vue │ │ ├── Start.vue │ │ └── Wizard.vue └── vue.config.js ├── LICENSE.md ├── ODrive_Workspace.code-workspace ├── README.md ├── analysis ├── Simulation │ ├── MotorSim.py │ └── TranslationalMass.py ├── cogging_torque │ └── cogging_harmonics.py ├── filterpoles.py ├── motor_analysis │ ├── 350kvTP.PNG │ ├── 350kvVelli.PNG │ ├── VelliPlot.m │ └── ac_induction_motor.py ├── numeric_path_opt │ ├── Main.m │ └── predictionmatrices.m └── thermistors.py ├── dockerbuild.sh ├── docs ├── Makefile ├── analog-input.rst ├── ascii-protocol.rst ├── assets │ └── css │ │ └── style.scss ├── can-guide.rst ├── can-protocol.rst ├── changelog.rst ├── commands.rst ├── conf.py ├── configuring-eclipse.rst ├── configuring-vscode.rst ├── control-modes.rst ├── control.rst ├── developer-guide.rst ├── encoders.rst ├── endstops.rst ├── exts │ └── fibre_autodoc.py ├── fibre_types │ └── com_odriverobotics_ODrive.rst ├── figures │ ├── CAN_Bus_Drawing.png │ ├── CodeAsMakefile.png │ ├── Endstop_configuration.png │ ├── ImportLaunch.png │ ├── LaunchConfigFilter.png │ ├── Non_Isolated_CAN_Wiring.png │ ├── ODriveBasicWiring.png │ ├── TrapTrajPosVel.PNG │ ├── can-protocol.csv │ ├── controller_with_ff.png │ ├── endstop_figure.png │ ├── ground_loop_bad.png │ ├── ground_loop_fix.png │ ├── liveplotter-iq-omega.png │ ├── liveplotter-pos-estimate.png │ ├── mech_dimensions.png │ ├── pinout.csv │ ├── secondOrderResponse.PNG │ ├── stlink-wiring.jpg │ ├── thermistor-voltage-divider.png │ └── torque_mode_vel_limit.png ├── getting-started.rst ├── ground-loops.rst ├── hoverboard.rst ├── index.rst ├── make.bat ├── migration.rst ├── native-protocol.rst ├── odrivetool.rst ├── pinout.rst ├── protocol.rst ├── rc-pwm.rst ├── specifications.rst ├── step-direction.rst ├── testing.rst ├── thermistors.rst ├── troubleshooting.rst ├── uart.rst └── usb.rst └── tools ├── .gitignore ├── .vscode └── launch.json ├── arduino_enums_template.j2 ├── can_async_example.py ├── can_dbc_example.py ├── can_example.py ├── create_can_dbc.py ├── enums_template.j2 ├── fibre-tools ├── fibre-shell ├── interface-schema.json ├── interface_generator.py ├── interface_parser.py ├── type_info.py └── type_registry.py ├── motion_planning └── PlanTrap.py ├── odrive-cansimple.dbc ├── odrive ├── __init__.py ├── configuration.py ├── dfu.py ├── dfuse │ ├── COPYING │ ├── DfuDevice.py │ ├── DfuFile.py │ ├── DfuState.py │ ├── DfuStatus.py │ └── __init__.py ├── enums.py ├── pyfibre │ ├── .gitattributes │ ├── .gitignore │ ├── README.md │ ├── fibre │ │ ├── __init__.py │ │ ├── libfibre-linux-aarch64.so │ │ ├── libfibre-linux-amd64.so │ │ ├── libfibre-linux-armhf.so │ │ ├── libfibre-macos-x86.dylib │ │ ├── libfibre-windows-amd64.dll │ │ ├── libfibre.py │ │ ├── libwinpthread-1.dll │ │ ├── protocol.py │ │ ├── shell.py │ │ └── utils.py │ └── setup.py ├── shell.py ├── tests │ ├── analog_input_test.py │ ├── calibration_test.py │ ├── can_test.py │ ├── closed_loop_test.py │ ├── dp800.py │ ├── encoder_test.py │ ├── endstop_manualtest.py │ ├── fibre_test.py │ ├── fighting_test.py │ ├── gpio_test.py │ ├── integration_test.py │ ├── not_a_test.py │ ├── nvm_test.py │ ├── old_tests.py │ ├── pwm_input_test.py │ ├── results.html.j2 │ ├── run_all_tests.sh │ ├── sensor_test.py │ ├── step_dir_test.py │ ├── test_runner.py │ └── uart_ascii_test.py ├── utils.py └── version.py ├── odrive_demo.py ├── odrive_header_template.h.in ├── odrivetool ├── odrivetool.bat ├── plot_oscilloscope.py ├── requirements.txt ├── run_tests.py ├── setup.py ├── setup_hall_as_index.py ├── test-rig-jw.yaml ├── test-rig-loopback.yaml ├── test-rig-parallel.yaml ├── test-rig-pj.yaml ├── test-rig-ss3.yaml ├── test-rig-ss4.yaml └── usbpermission /.github/ISSUE_TEMPLATE/bug_report.md: -------------------------------------------------------------------------------- 1 | --- 2 | name: Bug report 3 | about: Create a report to help us improve 4 | title: '' 5 | labels: bug 6 | assignees: '' 7 | 8 | --- 9 | 10 | **Describe the bug** 11 | A clear and concise description of what the bug is. 12 | 13 | **To Reproduce** 14 | Steps and configuration necessary to reproduce the behavior. 15 | 16 | **Expected behavior** 17 | A clear and concise description of what you expected to happen. 18 | 19 | **Desktop (please complete the following information):** 20 | - OS: [e.g. Windows 10] 21 | - odrivetool Version (`odrivetool --version`) 22 | 23 | **Additional context** 24 | Add any other context about the problem here. 25 | -------------------------------------------------------------------------------- /.github/ISSUE_TEMPLATE/feature_request.md: -------------------------------------------------------------------------------- 1 | --- 2 | name: Feature request 3 | about: Suggest an idea for this project 4 | title: '' 5 | labels: '' 6 | assignees: '' 7 | 8 | --- 9 | 10 | **Is your feature request related to a problem? Please describe.** 11 | A clear and concise description of what the problem is. Ex. I'm always frustrated when [...] 12 | 13 | **Describe the solution you'd like** 14 | A clear and concise description of what you want to happen. 15 | 16 | **Describe alternatives you've considered** 17 | A clear and concise description of any alternative solutions or features you've considered. 18 | 19 | **Additional context** 20 | Add any other context or screenshots about the feature request here. 21 | -------------------------------------------------------------------------------- /.github/actions/add-version-to-channel/action.yml: -------------------------------------------------------------------------------- 1 | name: 'Add version to release channel' 2 | description: | 3 | Appends the specified version to the end of the specified release channel if 4 | it wasn't already part of that channel. 5 | 6 | inputs: 7 | release_type: 8 | description: 'Release type (firmware, gui, docs, internal-docs).' 9 | required: true 10 | channel: 11 | description: 'The channel on which to register this version' 12 | required: true 13 | version: 14 | description: 'The version name (commit hash or semantic version name)' 15 | required: true 16 | odrive_api_key: 17 | description: 'Key to our release index server' 18 | required: true 19 | 20 | runs: 21 | using: "composite" 22 | steps: 23 | - name: Install Prerequisites 24 | shell: bash 25 | run: | 26 | pip install aiohttp cryptography 27 | pip install odrive --pre 28 | 29 | - name: Register on release server 30 | shell: python 31 | run: | 32 | import asyncio 33 | import sys 34 | import aiohttp 35 | 36 | sys.path.insert(0, '${{ github.workspace }}/.github/actions/upload-release') 37 | from odrive.api_client import ApiClient 38 | from private_release_api import PrivateReleaseApi 39 | 40 | async def main(): 41 | async with aiohttp.ClientSession() as session: 42 | api_client = ApiClient(session, key='${{ inputs.odrive_api_key }}') 43 | release_api = PrivateReleaseApi(api_client) 44 | await release_api.append_to_channel('${{ inputs.release_type }}', "${{ inputs.channel }}", "${{ inputs.version }}") 45 | await release_api.refresh_routes('${{ inputs.release_type }}') 46 | 47 | asyncio.run(main()) 48 | -------------------------------------------------------------------------------- /.github/workflows/documentation.yml: -------------------------------------------------------------------------------- 1 | name: Build and publish HTML documentation website 2 | 3 | on: 4 | push: 5 | branches: [ 'docs-v**' ] 6 | paths: ['docs/**', '.github/**'] 7 | 8 | jobs: 9 | make-html: 10 | runs-on: ubuntu-latest 11 | steps: 12 | - uses: actions/checkout@v2 13 | 14 | - name: Get release name and channel 15 | id: release-info 16 | shell: python 17 | run: | 18 | channel = "master" 19 | version = "${{ github.ref }}" 20 | assert version.startswith("refs/heads/docs-v0.5.") 21 | version = version[len("refs/heads/docs-v"):] 22 | 23 | print("::set-output name=channel::" + channel) 24 | print("::set-output name=version::" + version) 25 | 26 | - name: Cache pip 27 | uses: actions/cache@v2 28 | with: 29 | path: ~/.cache/pip 30 | key: ${{ runner.os }}-pip-sphinx-sphinx-tabs-sphinx-design-sphinx_copybutton-sphinx_panels-sphinx_rtd_theme 31 | restore-keys: | 32 | ${{ runner.os }}-pip- 33 | ${{ runner.os }}- 34 | 35 | - name: Install Python dependencies 36 | run: pip install sphinx sphinx-tabs sphinx-design sphinx_copybutton sphinx_panels sphinx_rtd_theme myst_parser 37 | 38 | - name: Build HTML docs 39 | run: | 40 | cd docs 41 | make html 42 | 43 | - name: Upload docs 44 | uses: ./.github/actions/upload-release 45 | with: 46 | release_type: docs 47 | version: ${{ steps.release-info.outputs.version }} 48 | src_dir: docs/_build/html 49 | do_access_key: ${{ secrets.DIGITALOCEAN_ACCESS_KEY }} 50 | do_secret_key: ${{ secrets.DIGITALOCEAN_SECRET_KEY }} 51 | odrive_api_key: ${{ secrets.ODRIVE_API_KEY }} 52 | variant: public 53 | 54 | - name: Add version to release channel 55 | uses: ./.github/actions/add-version-to-channel 56 | with: 57 | release_type: docs 58 | channel: ${{ steps.release-info.outputs.channel }} 59 | version: ${{ steps.release-info.outputs.version }} 60 | odrive_api_key: ${{ secrets.ODRIVE_API_KEY }} 61 | -------------------------------------------------------------------------------- /.gitignore: -------------------------------------------------------------------------------- 1 | # Byte-compiled / optimized / DLL files 2 | __pycache__/ 3 | *.py[cod] 4 | *$py.class 5 | 6 | # Unit test / coverage reports 7 | htmlcov/ 8 | .tox/ 9 | .coverage 10 | .coverage.* 11 | .cache 12 | nosetests.xml 13 | coverage.xml 14 | *,cover 15 | .hypothesis/ 16 | 17 | # Translations 18 | *.mo 19 | *.pot 20 | 21 | # Django stuff: 22 | *.log 23 | 24 | # PyBuilder 25 | target/ 26 | 27 | #Ipython Notebook 28 | .ipynb_checkpoints 29 | 30 | # Tup 31 | .tup 32 | tup.config 33 | 34 | # Sphinx documentation 35 | /docs/_build/ 36 | 37 | # Autogenerated API reference 38 | /docs/_api 39 | /docs/_includes/apiindex.html 40 | 41 | # Jekyll HTML documention and artifacts 42 | /docs/ruby-bundle 43 | /docs/_site 44 | /docs/.bundle/config 45 | /docs/.jekyll-metadata 46 | 47 | 48 | *.exe 49 | 50 | ODrive\.config 51 | 52 | ODrive\.creator 53 | 54 | ODrive\.creator\.user 55 | 56 | ODrive\.files 57 | 58 | ODrive\.includes 59 | 60 | Firmware/Tests/bin/ 61 | 62 | # GUI 63 | GUI/dist_electron 64 | GUI/node_modules 65 | GUI/build 66 | 67 | docs/reStructuredText/_build/ 68 | tools/odrive-cansimple.ini 69 | -------------------------------------------------------------------------------- /Arduino/ODriveArduino/LICENSE: -------------------------------------------------------------------------------- 1 | MIT License 2 | 3 | Copyright (c) 2017 Oskar Weigl 4 | 5 | Permission is hereby granted, free of charge, to any person obtaining a copy 6 | of this software and associated documentation files (the "Software"), to deal 7 | in the Software without restriction, including without limitation the rights 8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 9 | copies of the Software, and to permit persons to whom the Software is 10 | furnished to do so, subject to the following conditions: 11 | 12 | The above copyright notice and this permission notice shall be included in all 13 | copies or substantial portions of the Software. 14 | 15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 21 | SOFTWARE. 22 | -------------------------------------------------------------------------------- /Arduino/ODriveArduino/ODriveArduino.h: -------------------------------------------------------------------------------- 1 | 2 | #ifndef ODriveArduino_h 3 | #define ODriveArduino_h 4 | 5 | #include "Arduino.h" 6 | #include "ODriveEnums.h" 7 | 8 | class ODriveArduino { 9 | public: 10 | ODriveArduino(Stream& serial); 11 | 12 | // Commands 13 | void SetPosition(int motor_number, float position); 14 | void SetPosition(int motor_number, float position, float velocity_feedforward); 15 | void SetPosition(int motor_number, float position, float velocity_feedforward, float current_feedforward); 16 | void SetVelocity(int motor_number, float velocity); 17 | void SetVelocity(int motor_number, float velocity, float current_feedforward); 18 | void SetCurrent(int motor_number, float current); 19 | void TrapezoidalMove(int motor_number, float position); 20 | // Getters 21 | float GetVelocity(int motor_number); 22 | float GetPosition(int motor_number); 23 | // General params 24 | float readFloat(); 25 | int32_t readInt(); 26 | 27 | // State helper 28 | bool run_state(int axis, int requested_state, bool wait_for_idle, float timeout = 10.0f); 29 | private: 30 | String readString(); 31 | 32 | Stream& serial_; 33 | }; 34 | 35 | #endif //ODriveArduino_h 36 | -------------------------------------------------------------------------------- /Arduino/ODriveArduino/README.md: -------------------------------------------------------------------------------- 1 | # ODriveArduino 2 | Arduino library for the ODrive 3 | 4 | To install the library, first clone this repository. In the Arduino IDE select: *Sketch -> Include Library -> Add .ZIP Library...* 5 | 6 | Select the enclosing folder (e.g. ODriveArduino) to add it. Restarting the Arduino IDE may be necessary to see the examples in the *File* dropdown. Check the included example *ODriveArduinoTest* for basic usage. 7 | -------------------------------------------------------------------------------- /Dockerfile: -------------------------------------------------------------------------------- 1 | FROM ubuntu:bionic 2 | 3 | # Prepare the build environment and dependencies 4 | RUN \ 5 | set -x && \ 6 | apt-get update && \ 7 | apt-get -y install software-properties-common && \ 8 | add-apt-repository ppa:team-gcc-arm-embedded/ppa && \ 9 | add-apt-repository ppa:jonathonf/tup && \ 10 | apt-get update && \ 11 | apt-get -y upgrade && \ 12 | apt-get -y install gcc-arm-embedded openocd tup python3.7 python3-yaml python3-jinja2 python3-jsonschema build-essential git time && \ 13 | # Build step below does not know about debian's python naming schemme 14 | ln -s /usr/bin/python3.7 /usr/bin/python && \ 15 | mkdir -p ODrive 16 | 17 | WORKDIR ODrive/Firmware 18 | 19 | # Must attach the firmware tree into the container 20 | CMD \ 21 | # Regenerate autogen/version.c 22 | mkdir -p autogen && \ 23 | python ../tools/odrive/version.py \ 24 | --output autogen/version.c && \ 25 | # Regenerate python interface 26 | python interface_generator_stub.py \ 27 | --definitions odrive-interface.yaml \ 28 | --template ../tools/enums_template.j2 \ 29 | --output ../tools/odrive/enums.py && \ 30 | python interface_generator_stub.py \ 31 | --definitions odrive-interface.yaml \ 32 | --template ../tools/arduino_enums_template.j2 \ 33 | --output ../Arduino/ODriveArduino/ODriveEnums.h && \ 34 | # Hack around Tup's dependency on FUSE 35 | tup init && \ 36 | tup generate build.sh && \ 37 | ./build.sh 38 | -------------------------------------------------------------------------------- /Firmware/.clang-format: -------------------------------------------------------------------------------- 1 | --- 2 | BasedOnStyle: Google 3 | AllowShortCaseLabelsOnASingleLine: 'true' 4 | IndentWidth: '4' 5 | ColumnLimit: '0' 6 | ... 7 | -------------------------------------------------------------------------------- /Firmware/.gitignore: -------------------------------------------------------------------------------- 1 | 2 | #build folder 3 | autogen/ 4 | build/ 5 | deploy/ 6 | .dep/ 7 | tup_build.sh 8 | 9 | #markdown preview output 10 | README.html 11 | 12 | #autogenerated project files 13 | .cproject 14 | .mxproject 15 | Odrive.xml 16 | 17 | #Eclipse stuff 18 | .settings/ 19 | .project 20 | 21 | # VSCode stuff 22 | /.vscode/.cortex-debug.*.state.json 23 | 24 | # STM32CubeMX (in case you put it in this folder, or a symlink) 25 | STM32CubeMX 26 | 27 | #gdb log 28 | openocd.log 29 | 30 | # OS-specific files 31 | .DS_Store -------------------------------------------------------------------------------- /Firmware/.vscode/settings.json: -------------------------------------------------------------------------------- 1 | { 2 | "C_Cpp.intelliSenseEngine": "Default", 3 | "C_Cpp.intelliSenseEngineFallback": "Disabled", 4 | "files.associations": { 5 | "memory": "cpp", 6 | "utility": "cpp", 7 | "deque": "cpp", 8 | "vector": "cpp", 9 | "array": "cpp", 10 | "*.tcc": "cpp", 11 | "cctype": "cpp", 12 | "clocale": "cpp", 13 | "cstdint": "cpp", 14 | "cstdio": "cpp", 15 | "cstdlib": "cpp", 16 | "cstring": "cpp", 17 | "cwchar": "cpp", 18 | "cwctype": "cpp", 19 | "exception": "cpp", 20 | "functional": "cpp", 21 | "initializer_list": "cpp", 22 | "iosfwd": "cpp", 23 | "istream": "cpp", 24 | "limits": "cpp", 25 | "new": "cpp", 26 | "ostream": "cpp", 27 | "stdexcept": "cpp", 28 | "streambuf": "cpp", 29 | "string_view": "cpp", 30 | "system_error": "cpp", 31 | "tuple": "cpp", 32 | "type_traits": "cpp", 33 | "typeinfo": "cpp", 34 | "algorithm": "cpp" 35 | } 36 | } -------------------------------------------------------------------------------- /Firmware/.vscode/tasks.json: -------------------------------------------------------------------------------- 1 | { 2 | // See https://go.microsoft.com/fwlink/?LinkId=733558 3 | // for the documentation about the tasks.json format 4 | "version": "2.0.0", 5 | "tasks": [ 6 | { 7 | "label": "build", 8 | "type": "shell", 9 | "command": "make", 10 | "group": { 11 | "kind": "build", 12 | "isDefault": true 13 | }, 14 | "presentation": { 15 | "panel": "new" 16 | }, 17 | "problemMatcher": [ 18 | "$gcc" 19 | ] 20 | }, 21 | { 22 | "label": "flash - ST-Link", 23 | "type": "shell", 24 | "command": "make flash", 25 | "problemMatcher": [] 26 | }, 27 | { 28 | "label": "flash - Black Magic Probe", 29 | "type": "shell", 30 | "command": "make flashbmp", 31 | "problemMatcher": [] 32 | }, 33 | { 34 | "label": "openocd", 35 | "type": "shell", 36 | "command": "openocd -f \"interface/stlink-v2.cfg\" -f \"target/stm32f4x_stlink.cfg\" -c \"gdb_port 3333; log_output openocd.log\"", 37 | "problemMatcher": [] 38 | } 39 | ] 40 | } 41 | -------------------------------------------------------------------------------- /Firmware/Board/v3/Src/prev_board_ver/gpio_V3_4.c: -------------------------------------------------------------------------------- 1 | /** Configure pins as 2 | * Analog 3 | * Input 4 | * Output 5 | * EVENT_OUT 6 | * EXTI 7 | */ 8 | void MX_GPIO_Init(void) 9 | { 10 | 11 | GPIO_InitTypeDef GPIO_InitStruct; 12 | 13 | /* GPIO Ports Clock Enable */ 14 | __HAL_RCC_GPIOC_CLK_ENABLE(); 15 | __HAL_RCC_GPIOH_CLK_ENABLE(); 16 | __HAL_RCC_GPIOA_CLK_ENABLE(); 17 | __HAL_RCC_GPIOB_CLK_ENABLE(); 18 | __HAL_RCC_GPIOD_CLK_ENABLE(); 19 | 20 | /*Configure GPIO pin Output Level */ 21 | HAL_GPIO_WritePin(GPIOC, M0_nCS_Pin|M1_nCS_Pin, GPIO_PIN_SET); 22 | 23 | /*Configure GPIO pin Output Level */ 24 | HAL_GPIO_WritePin(GPIOC, M1_DC_CAL_Pin|M0_DC_CAL_Pin, GPIO_PIN_RESET); 25 | 26 | /*Configure GPIO pin Output Level */ 27 | HAL_GPIO_WritePin(EN_GATE_GPIO_Port, EN_GATE_Pin, GPIO_PIN_RESET); 28 | 29 | /*Configure GPIO pins : PCPin PCPin PCPin PCPin */ 30 | GPIO_InitStruct.Pin = M0_nCS_Pin|M1_nCS_Pin|M1_DC_CAL_Pin|M0_DC_CAL_Pin; 31 | GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; 32 | GPIO_InitStruct.Pull = GPIO_NOPULL; 33 | GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; 34 | HAL_GPIO_Init(GPIOC, &GPIO_InitStruct); 35 | 36 | /*Configure GPIO pin : PtPin */ 37 | GPIO_InitStruct.Pin = GPIO_3_Pin; 38 | GPIO_InitStruct.Mode = GPIO_MODE_IT_RISING; 39 | GPIO_InitStruct.Pull = GPIO_PULLDOWN; 40 | HAL_GPIO_Init(GPIO_3_GPIO_Port, &GPIO_InitStruct); 41 | 42 | /*Configure GPIO pins : PAPin PAPin */ 43 | GPIO_InitStruct.Pin = GPIO_4_Pin|M0_ENC_Z_Pin; 44 | GPIO_InitStruct.Mode = GPIO_MODE_INPUT; 45 | GPIO_InitStruct.Pull = GPIO_NOPULL; 46 | HAL_GPIO_Init(GPIOA, &GPIO_InitStruct); 47 | 48 | /*Configure GPIO pins : PBPin PBPin */ 49 | GPIO_InitStruct.Pin = GPIO_5_Pin|M1_ENC_Z_Pin; 50 | GPIO_InitStruct.Mode = GPIO_MODE_INPUT; 51 | GPIO_InitStruct.Pull = GPIO_NOPULL; 52 | HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); 53 | 54 | /*Configure GPIO pin : PtPin */ 55 | GPIO_InitStruct.Pin = EN_GATE_Pin; 56 | GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; 57 | GPIO_InitStruct.Pull = GPIO_NOPULL; 58 | GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; 59 | HAL_GPIO_Init(EN_GATE_GPIO_Port, &GPIO_InitStruct); 60 | 61 | /*Configure GPIO pin : PtPin */ 62 | GPIO_InitStruct.Pin = nFAULT_Pin; 63 | GPIO_InitStruct.Mode = GPIO_MODE_INPUT; 64 | GPIO_InitStruct.Pull = GPIO_PULLUP; 65 | HAL_GPIO_Init(nFAULT_GPIO_Port, &GPIO_InitStruct); 66 | 67 | /* EXTI interrupt init*/ 68 | HAL_NVIC_SetPriority(EXTI2_IRQn, 0, 0); 69 | HAL_NVIC_EnableIRQ(EXTI2_IRQn); 70 | 71 | } 72 | -------------------------------------------------------------------------------- /Firmware/Drivers/STM32/stm32_nvm.h: -------------------------------------------------------------------------------- 1 | /* Define to prevent recursive inclusion -------------------------------------*/ 2 | #ifndef __NVM_H 3 | #define __NVM_H 4 | 5 | #ifdef __cplusplus 6 | extern "C" { 7 | #endif 8 | 9 | /* Includes ------------------------------------------------------------------*/ 10 | #include 11 | #include 12 | 13 | /* Exported types ------------------------------------------------------------*/ 14 | /* Exported constants --------------------------------------------------------*/ 15 | /* Exported variables --------------------------------------------------------*/ 16 | /* Exported macro ------------------------------------------------------------*/ 17 | /* Exported functions --------------------------------------------------------*/ 18 | 19 | int NVM_init(void); 20 | int NVM_erase(void); 21 | size_t NVM_get_max_read_length(void); 22 | size_t NVM_get_max_write_length(void); 23 | int NVM_read(size_t offset, uint8_t *data, size_t length); 24 | int NVM_start_write(size_t length); 25 | int NVM_write(size_t offset, uint8_t *data, size_t length); 26 | int NVM_commit(void); 27 | void NVM_demo(void); 28 | 29 | #ifdef __cplusplus 30 | } 31 | #endif 32 | 33 | #endif //__NVM_H -------------------------------------------------------------------------------- /Firmware/Drivers/STM32/stm32_system.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include "stm32_system.h" 3 | 4 | uint32_t irq_counters[254]; // 14 core interrupts, 240 NVIC interrupts 5 | -------------------------------------------------------------------------------- /Firmware/Drivers/STM32/stm32_system.h: -------------------------------------------------------------------------------- 1 | #ifndef __STM32_SYSTEM_H 2 | #define __STM32_SYSTEM_H 3 | 4 | #if defined(STM32F405xx) 5 | #include 6 | #elif defined(STM32F722xx) 7 | #include 8 | #else 9 | #error "unknown STM32 microcontroller" 10 | #endif 11 | 12 | // C/C++ definitions 13 | 14 | #ifdef __cplusplus 15 | extern "C" { 16 | #endif 17 | 18 | // Uncomment the following line to sacrifice 1kB of RAM for the ability to 19 | // monitor the number of times each interrupt fires. 20 | //#define ENABLE_IRQ_COUNTER 21 | 22 | #ifdef ENABLE_IRQ_COUNTER 23 | extern uint32_t irq_counters[]; 24 | #define COUNT_IRQ(irqn) (++irq_counters[irqn + 14]) 25 | #define GET_IRQ_COUNTER(irqn) irq_counters[irqn + 14] 26 | #else 27 | #define COUNT_IRQ(irqn) ((void)0) 28 | #define GET_IRQ_COUNTER(irqn) 0 29 | #endif 30 | 31 | static inline uint32_t cpu_enter_critical() { 32 | uint32_t primask = __get_PRIMASK(); 33 | __disable_irq(); 34 | return primask; 35 | } 36 | 37 | static inline void cpu_exit_critical(uint32_t priority_mask) { 38 | __set_PRIMASK(priority_mask); 39 | } 40 | 41 | #ifdef __cplusplus 42 | } 43 | #endif 44 | 45 | 46 | // C++ only definitions 47 | 48 | #ifdef __cplusplus 49 | 50 | struct CriticalSectionContext { 51 | CriticalSectionContext(const CriticalSectionContext&) = delete; 52 | CriticalSectionContext(const CriticalSectionContext&&) = delete; 53 | void operator=(const CriticalSectionContext&) = delete; 54 | void operator=(const CriticalSectionContext&&) = delete; 55 | operator bool() { return true; }; 56 | CriticalSectionContext() : mask_(cpu_enter_critical()) {} 57 | ~CriticalSectionContext() { cpu_exit_critical(mask_); } 58 | uint32_t mask_; 59 | bool exit_ = false; 60 | }; 61 | 62 | #ifdef __clang__ 63 | #define CRITICAL_SECTION() for (CriticalSectionContext __critical_section_context; !__critical_section_context.exit_; __critical_section_context.exit_ = true) 64 | #else 65 | #define CRITICAL_SECTION() if (CriticalSectionContext __critical_section_context{}) 66 | #endif 67 | 68 | #endif 69 | 70 | #endif // __STM32_SYSTEM_H -------------------------------------------------------------------------------- /Firmware/Drivers/gate_driver.hpp: -------------------------------------------------------------------------------- 1 | #ifndef __GATE_DRIVER_HPP 2 | #define __GATE_DRIVER_HPP 3 | 4 | struct GateDriverBase { 5 | /** 6 | * @brief Unlocks or locks the gate signals of the gate driver. 7 | * 8 | * While locked the PWM inputs are ignored and the switches are always in 9 | * OFF state. 10 | * Not all gate drivers implement this function and may return true even if 11 | * the gate driver was not locked. 12 | */ 13 | virtual bool set_enabled(bool enabled) = 0; 14 | 15 | /** 16 | * @brief Returns false if the gate driver is in a state where the output 17 | * drive stages are disarmed or not properly configured (e.g. because they 18 | * are not initialized or there was a fault condition). 19 | */ 20 | virtual bool is_ready() = 0; 21 | }; 22 | 23 | struct OpAmpBase { 24 | /** 25 | * @brief Returns false if the opamp is in a state where it's not operating 26 | * with the latest configured gain (e.g. because it was not initialized or 27 | * there was a fault condition). 28 | */ 29 | virtual bool is_ready() = 0; 30 | 31 | /** 32 | * @brief Returns the neutral voltage of the OpAmp in Volts 33 | */ 34 | virtual float get_midpoint() = 0; 35 | 36 | /** 37 | * @brief Returns the maximum voltage swing away from the midpoint voltage (in Volts) 38 | */ 39 | virtual float get_max_output_swing() = 0; 40 | }; 41 | 42 | #endif // __GATE_DRIVER_HPP -------------------------------------------------------------------------------- /Firmware/FreeRTOS-openocd.c: -------------------------------------------------------------------------------- 1 | /* 2 | * Since at least FreeRTOS V7.5.3 uxTopUsedPriority is no longer 3 | * present in the kernel, so it has to be supplied by other means for 4 | * OpenOCD's threads awareness. 5 | * 6 | * Add this file to your project, and, if you're using --gc-sections, 7 | * ``--undefined=uxTopUsedPriority'' (or 8 | * ``-Wl,--undefined=uxTopUsedPriority'' when using gcc for final 9 | * linking) to your LDFLAGS; same with all the other symbols you need. 10 | */ 11 | 12 | #include "FreeRTOS.h" 13 | 14 | #ifdef __GNUC__ 15 | #define USED __attribute__((used)) 16 | #else 17 | #define USED 18 | #endif 19 | 20 | const int USED uxTopUsedPriority = configMAX_PRIORITIES - 1; 21 | -------------------------------------------------------------------------------- /Firmware/LICENSE: -------------------------------------------------------------------------------- 1 | The MIT License (MIT) 2 | 3 | Copyright (c) 2016-2018 Oskar Weigl 4 | 5 | Permission is hereby granted, free of charge, to any person obtaining a copy 6 | of this software and associated documentation files (the "Software"), to deal 7 | in the Software without restriction, including without limitation the rights 8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 9 | copies of the Software, and to permit persons to whom the Software is 10 | furnished to do so, subject to the following conditions: 11 | 12 | The above copyright notice and this permission notice shall be included in all 13 | copies or substantial portions of the Software. 14 | 15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 21 | SOFTWARE. 22 | -------------------------------------------------------------------------------- /Firmware/MotorControl/acim_estimator.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include "acim_estimator.hpp" 3 | #include 4 | 5 | void AcimEstimator::update(uint32_t timestamp) { 6 | std::optional rotor_phase = rotor_phase_src_.present(); 7 | std::optional rotor_phase_vel = rotor_phase_vel_src_.present(); 8 | std::optional idq = idq_src_.present(); 9 | 10 | if (!rotor_phase.has_value() || !rotor_phase_vel.has_value() || !idq.has_value()) { 11 | active_ = false; 12 | return; 13 | } 14 | 15 | auto [id, iq] = *idq; 16 | 17 | float dt = (float)(timestamp - last_timestamp_) / (float)TIM_1_8_CLOCK_HZ; 18 | last_timestamp_ = timestamp; 19 | 20 | if (!active_) { 21 | // Skip first iteration and use it to reset state 22 | rotor_flux_ = 0.0f; 23 | phase_offset_ = 0.0f; 24 | active_ = true; 25 | return; 26 | } 27 | 28 | // Note that the effect of the current commands on the real currents is actually 1.5 PWM cycles later 29 | // However the rotor time constant is (usually) so slow that it doesn't matter 30 | // So we elect to write it as if the effect is immediate, to have cleaner code 31 | 32 | // acim_rotor_flux is normalized to units of [A] tracking Id; rotor inductance is unspecified 33 | float dflux_by_dt = config_.slip_velocity * (id - rotor_flux_); 34 | rotor_flux_ += dflux_by_dt * dt; 35 | float slip_velocity = config_.slip_velocity * (iq / rotor_flux_); 36 | // Check for issues with small denominator. 37 | if (is_nan(slip_velocity) || (std::abs(slip_velocity) > 0.1f / dt)) { 38 | slip_velocity = 0.0f; 39 | } 40 | slip_vel_ = slip_velocity; // reporting only 41 | 42 | stator_phase_vel_ = *rotor_phase_vel + slip_velocity; 43 | phase_offset_ = wrap_pm_pi(phase_offset_ + slip_velocity * dt); 44 | stator_phase_ = wrap_pm_pi(*rotor_phase + phase_offset_); 45 | } 46 | -------------------------------------------------------------------------------- /Firmware/MotorControl/acim_estimator.hpp: -------------------------------------------------------------------------------- 1 | #ifndef __ACIM_ESTIMATOR_HPP 2 | #define __ACIM_ESTIMATOR_HPP 3 | 4 | #include 5 | #include 6 | #include 7 | 8 | class AcimEstimator : public ComponentBase { 9 | public: 10 | struct Config_t { 11 | float slip_velocity = 14.706f; // [rad/s electrical] = 1/rotor_tau 12 | }; 13 | 14 | void update(uint32_t timestamp) final; 15 | 16 | // Config 17 | Config_t config_; 18 | 19 | // Inputs 20 | InputPort rotor_phase_src_; 21 | InputPort rotor_phase_vel_src_; 22 | InputPort idq_src_; 23 | 24 | // State variables 25 | bool active_ = false; 26 | uint32_t last_timestamp_ = 0; 27 | float rotor_flux_ = 0.0f; // [A] 28 | float phase_offset_ = 0.0f; // [A] 29 | 30 | // Outputs 31 | OutputPort slip_vel_ = 0.0f; // [rad/s electrical] 32 | OutputPort stator_phase_vel_ = 0.0f; // [rad/s] rotor flux angular velocity estimate 33 | OutputPort stator_phase_ = 0.0f; // [rad] rotor flux phase angle estimate 34 | }; 35 | 36 | #endif // __ACIM_ESTIMATOR_HPP -------------------------------------------------------------------------------- /Firmware/MotorControl/current_limiter.hpp: -------------------------------------------------------------------------------- 1 | #ifndef __CURRENT_LIMITER_HPP 2 | #define __CURRENT_LIMITER_HPP 3 | 4 | class CurrentLimiter { 5 | public: 6 | virtual ~CurrentLimiter() = default; 7 | virtual float get_current_limit(float base_current_lim) const = 0; 8 | }; 9 | 10 | #endif // __CURRENT_LIMITER_HPP 11 | -------------------------------------------------------------------------------- /Firmware/MotorControl/endstop.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | 4 | void Endstop::update() { 5 | debounceTimer_.update(); 6 | last_state_ = endstop_state_; 7 | if (config_.enabled) { 8 | bool last_pin_state = pin_state_; 9 | 10 | pin_state_ = get_gpio(config_.gpio_num).read(); 11 | 12 | // If the pin state has changed, reset the timer 13 | if (pin_state_ != last_pin_state) 14 | debounceTimer_.reset(); 15 | 16 | if (debounceTimer_.expired()) 17 | endstop_state_ = config_.is_active_high ? pin_state_ : !pin_state_; // endstop_state is the logical state 18 | } else { 19 | endstop_state_ = false; 20 | } 21 | } 22 | 23 | bool Endstop::apply_config() { 24 | debounceTimer_.reset(); 25 | if (config_.enabled) { 26 | debounceTimer_.start(); 27 | } else { 28 | debounceTimer_.stop(); 29 | } 30 | debounceTimer_.setIncrement(config_.debounce_ms * 0.001f); 31 | return true; 32 | } 33 | -------------------------------------------------------------------------------- /Firmware/MotorControl/endstop.hpp: -------------------------------------------------------------------------------- 1 | #ifndef __ENDSTOP_HPP 2 | #define __ENDSTOP_HPP 3 | 4 | #include "timer.hpp" 5 | class Endstop { 6 | public: 7 | struct Config_t { 8 | float offset = 0; 9 | uint32_t debounce_ms = 50; 10 | uint16_t gpio_num = 0; 11 | bool enabled = false; 12 | bool is_active_high = false; 13 | 14 | // custom setters 15 | Endstop* parent = nullptr; 16 | void set_gpio_num(uint16_t value) { gpio_num = value; parent->apply_config(); } 17 | void set_enabled(uint32_t value) { enabled = value; parent->apply_config(); } 18 | void set_debounce_ms(uint32_t value) { debounce_ms = value; parent->apply_config(); } 19 | }; 20 | 21 | 22 | Endstop::Config_t config_; 23 | Axis* axis_ = nullptr; 24 | 25 | bool apply_config(); 26 | 27 | void update(); 28 | constexpr bool get_state(){ 29 | return endstop_state_; 30 | } 31 | 32 | constexpr bool rose(){ 33 | return (endstop_state_ != last_state_) && endstop_state_; 34 | } 35 | 36 | constexpr bool fell(){ 37 | return (endstop_state_ != last_state_) && !endstop_state_; 38 | } 39 | 40 | bool endstop_state_ = false; 41 | 42 | private: 43 | bool last_state_ = false; 44 | bool pin_state_ = false; 45 | float pos_when_pressed_ = 0.0f; 46 | Timer debounceTimer_; 47 | }; 48 | #endif -------------------------------------------------------------------------------- /Firmware/MotorControl/example.json: -------------------------------------------------------------------------------- 1 | [ 2 | { 3 | "name": "", 4 | "id": 0, 5 | "type": "json" 6 | }, 7 | { 8 | "name": "subscriptions", 9 | "id": 1, 10 | "type": "int32[]" 11 | }, 12 | { 13 | "name": "motor0", 14 | "id": 2, 15 | "type": "tree", 16 | "content": [ 17 | { 18 | "name": "pos_setpoint", 19 | "id": 3, 20 | "type": "float", 21 | "access": "rw" 22 | }, 23 | { 24 | "name": "pos_gain", 25 | "id": 4, 26 | "type": "float", 27 | "access": "rw" 28 | }, 29 | { 30 | "name": "vel_setpoint", 31 | "id": 5, 32 | "type": "float", 33 | "access": "rw" 34 | } 35 | ] 36 | } 37 | ] -------------------------------------------------------------------------------- /Firmware/MotorControl/foc.hpp: -------------------------------------------------------------------------------- 1 | #ifndef __FOC_HPP 2 | #define __FOC_HPP 3 | 4 | #include "phase_control_law.hpp" 5 | #include "component.hpp" 6 | 7 | /** 8 | * @brief Field oriented controller. 9 | * 10 | * This controller can run in either current control mode or voltage control 11 | * mode. 12 | */ 13 | class FieldOrientedController : public AlphaBetaFrameController, public ComponentBase { 14 | public: 15 | void update(uint32_t timestamp) final; 16 | 17 | void reset() final; 18 | 19 | ODriveIntf::MotorIntf::Error on_measurement( 20 | std::optional vbus_voltage, 21 | std::optional Ialpha_beta, 22 | uint32_t input_timestamp) final; 23 | 24 | ODriveIntf::MotorIntf::Error get_alpha_beta_output( 25 | uint32_t output_timestamp, 26 | std::optional* mod_alpha_beta, 27 | std::optional* ibus) final; 28 | 29 | // Config - these values are set while this controller is inactive 30 | std::optional pi_gains_; // [V/A, V/As] should be auto set after resistance and inductance measurement 31 | float I_measured_report_filter_k_ = 1.0f; 32 | 33 | // Inputs 34 | bool enable_current_control_src_ = false; 35 | InputPort Idq_setpoint_src_; 36 | InputPort Vdq_setpoint_src_; 37 | InputPort phase_src_; 38 | InputPort phase_vel_src_; 39 | 40 | // These values are set atomically by the update() function and read by the 41 | // calculate() function in an interrupt context. 42 | uint32_t ctrl_timestamp_; // [HCLK ticks] 43 | bool enable_current_control_ = false; // true: FOC runs in current control mode using I{dq}_setpoint, false: FOC runs in voltage control mode using V{dq}_setpoint 44 | std::optional Idq_setpoint_; // [A] only used if enable_current_control_ == true 45 | std::optional Vdq_setpoint_; // [V] feed-forward voltage term (or standalone setpoint if enable_current_control_ == false) 46 | std::optional phase_; // [rad] 47 | std::optional phase_vel_; // [rad/s] 48 | 49 | // These values (or some of them) are updated inside on_measurement() and get_alpha_beta_output() 50 | uint32_t i_timestamp_; 51 | std::optional vbus_voltage_measured_; // [V] 52 | std::optional Ialpha_beta_measured_; // [A, A] 53 | float Id_measured_; // [A] 54 | float Iq_measured_; // [A] 55 | float v_current_control_integral_d_ = 0.0f; // [V] 56 | float v_current_control_integral_q_ = 0.0f; // [V] 57 | //float mod_to_V_ = 0.0f; 58 | //float mod_d_ = 0.0f; 59 | //float mod_q_ = 0.0f; 60 | //float ibus_ = 0.0f; 61 | float final_v_alpha_ = 0.0f; // [V] 62 | float final_v_beta_ = 0.0f; // [V] 63 | float power_ = 0.0f; // [W] dot product of Vdq and Idq 64 | }; 65 | 66 | #endif // __FOC_HPP -------------------------------------------------------------------------------- /Firmware/MotorControl/low_level.h: -------------------------------------------------------------------------------- 1 | /* Define to prevent recursive inclusion -------------------------------------*/ 2 | #ifndef __LOW_LEVEL_H 3 | #define __LOW_LEVEL_H 4 | 5 | #ifdef __cplusplus 6 | extern "C" { 7 | #endif 8 | 9 | /* Includes ------------------------------------------------------------------*/ 10 | #include 11 | #include 12 | #include 13 | 14 | /* Exported types ------------------------------------------------------------*/ 15 | /* Exported constants --------------------------------------------------------*/ 16 | #define ADC_CHANNEL_COUNT 16 17 | extern const float adc_full_scale; 18 | extern const float adc_ref_voltage; 19 | /* Exported variables --------------------------------------------------------*/ 20 | extern float vbus_voltage; 21 | extern float ibus_; 22 | extern bool brake_resistor_armed; 23 | extern bool brake_resistor_saturated; 24 | extern float brake_resistor_current; 25 | extern uint16_t adc_measurements_[ADC_CHANNEL_COUNT]; 26 | extern osThreadId analog_thread; 27 | extern const uint32_t stack_size_analog_thread; 28 | /* Exported macro ------------------------------------------------------------*/ 29 | /* Exported functions --------------------------------------------------------*/ 30 | 31 | void safety_critical_arm_brake_resistor(); 32 | void safety_critical_disarm_brake_resistor(); 33 | void safety_critical_apply_brake_resistor_timings(uint32_t low_off, uint32_t high_on); 34 | 35 | // called from STM platform code 36 | extern "C" { 37 | void vbus_sense_adc_cb(uint32_t adc_value); 38 | void pwm_in_cb(TIM_HandleTypeDef *htim); 39 | } 40 | 41 | // Initalisation 42 | void start_adc_pwm(); 43 | void start_pwm(TIM_HandleTypeDef* htim); 44 | void sync_timers(TIM_HandleTypeDef* htim_a, TIM_HandleTypeDef* htim_b, 45 | uint16_t TIM_CLOCKSOURCE_ITRx, uint16_t count_offset, 46 | TIM_HandleTypeDef* htim_refbase = nullptr); 47 | void start_general_purpose_adc(); 48 | void pwm_in_init(); 49 | void start_analog_thread(); 50 | 51 | // ADC getters 52 | uint16_t channel_from_gpio(Stm32Gpio gpio); 53 | float get_adc_voltage(Stm32Gpio gpio); 54 | float get_adc_relative_voltage(Stm32Gpio gpio); 55 | float get_adc_relative_voltage_ch(uint16_t channel); 56 | 57 | void update_brake_current(); 58 | 59 | #ifdef __cplusplus 60 | } 61 | #endif 62 | 63 | #endif //__LOW_LEVEL_H 64 | -------------------------------------------------------------------------------- /Firmware/MotorControl/mechanical_brake.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | void MechanicalBrake::engage() { 4 | if (odrv.config_.gpio_modes[config_.gpio_num] == ODriveIntf::GPIO_MODE_MECH_BRAKE){ 5 | get_gpio(config_.gpio_num).write(config_.is_active_low ? 0 : 1); 6 | } 7 | } 8 | 9 | void MechanicalBrake::release() { 10 | if (odrv.config_.gpio_modes[config_.gpio_num] == ODriveIntf::GPIO_MODE_MECH_BRAKE){ 11 | get_gpio(config_.gpio_num).write(config_.is_active_low ? 1 : 0); 12 | } 13 | } 14 | -------------------------------------------------------------------------------- /Firmware/MotorControl/mechanical_brake.hpp: -------------------------------------------------------------------------------- 1 | #ifndef __MECHANICAL_BRAKE_HPP 2 | #define __MECHANICAL_BRAKE_HPP 3 | 4 | #include 5 | 6 | class MechanicalBrake : public ODriveIntf::MechanicalBrakeIntf { 7 | public: 8 | struct Config_t { 9 | uint16_t gpio_num = 0; 10 | bool is_active_low = true; 11 | 12 | // custom setters 13 | MechanicalBrake* parent = nullptr; 14 | void set_gpio_num(uint16_t value) { gpio_num = value; } 15 | }; 16 | 17 | MechanicalBrake() {} 18 | 19 | MechanicalBrake::Config_t config_; 20 | Axis* axis_ = nullptr; 21 | 22 | void release(); 23 | void engage(); 24 | }; 25 | #endif // __MECHANICAL_BRAKE_HPP -------------------------------------------------------------------------------- /Firmware/MotorControl/open_loop_controller.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include "open_loop_controller.hpp" 3 | #include 4 | 5 | void OpenLoopController::update(uint32_t timestamp) { 6 | auto [prev_Id, prev_Iq] = Idq_setpoint_.previous().value_or(float2D{0.0f, 0.0f}); 7 | auto [prev_Vd, prev_Vq] = Vdq_setpoint_.previous().value_or(float2D{0.0f, 0.0f}); 8 | float phase = phase_.previous().value_or(initial_phase_); 9 | float phase_vel = phase_vel_.previous().value_or(0.0f); 10 | 11 | (void)prev_Iq; // unused 12 | (void)prev_Vq; // unused 13 | 14 | float dt = (float)(timestamp - timestamp_) / (float)TIM_1_8_CLOCK_HZ; 15 | 16 | Idq_setpoint_ = { 17 | std::clamp(target_current_, prev_Id - max_current_ramp_ * dt, prev_Id + max_current_ramp_ * dt), 18 | 0.0f 19 | }; 20 | Vdq_setpoint_ = { 21 | std::clamp(target_voltage_, prev_Vd - max_voltage_ramp_ * dt, prev_Vd + max_voltage_ramp_ * dt), 22 | 0.0f 23 | }; 24 | 25 | phase_vel = std::clamp(target_vel_, phase_vel - max_phase_vel_ramp_ * dt, phase_vel + max_phase_vel_ramp_ * dt); 26 | phase_vel_ = phase_vel; 27 | phase_ = wrap_pm_pi(phase + phase_vel * dt); 28 | total_distance_ = total_distance_.previous().value_or(0.0f) + phase_vel * dt; 29 | timestamp_ = timestamp; 30 | } 31 | -------------------------------------------------------------------------------- /Firmware/MotorControl/open_loop_controller.hpp: -------------------------------------------------------------------------------- 1 | #ifndef __OPEN_LOOP_CONTROLLER_HPP 2 | #define __OPEN_LOOP_CONTROLLER_HPP 3 | 4 | #include "component.hpp" 5 | #include 6 | #include 7 | 8 | class OpenLoopController : public ComponentBase { 9 | public: 10 | void update(uint32_t timestamp) final; 11 | 12 | // Config 13 | float max_current_ramp_ = INFINITY; // [A/s] 14 | float max_voltage_ramp_ = INFINITY; // [V/s] 15 | float max_phase_vel_ramp_ = INFINITY; // [rad/s^2] 16 | 17 | // Inputs 18 | float target_vel_ = 0.0f; 19 | float target_current_ = 0.0f; 20 | float target_voltage_ = 0.0f; 21 | float initial_phase_ = 0.0f; 22 | 23 | // State/Outputs 24 | uint32_t timestamp_ = 0; 25 | OutputPort Idq_setpoint_ = {{0.0f, 0.0f}}; 26 | OutputPort Vdq_setpoint_ = {{0.0f, 0.0f}}; 27 | OutputPort phase_ = 0.0f; 28 | OutputPort phase_vel_ = 0.0f; 29 | OutputPort total_distance_ = 0.0f; 30 | }; 31 | 32 | #endif // __OPEN_LOOP_CONTROLLER_HPP -------------------------------------------------------------------------------- /Firmware/MotorControl/oscilloscope.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include "oscilloscope.hpp" 3 | 4 | // if you use the oscilloscope feature you can bump up this value 5 | #define OSCILLOSCOPE_SIZE 4096 6 | 7 | void Oscilloscope::update() { 8 | float trigger_data = trigger_src_ ? *trigger_src_ : 0.0f; 9 | float trigger_threshold = trigger_threshold_; 10 | float sample_data = data_src_ ? **data_src_ : 0.0f; 11 | 12 | if (trigger_data < trigger_threshold) { 13 | ready_ = true; 14 | } 15 | if (ready_ && trigger_data >= trigger_threshold) { 16 | capturing_ = true; 17 | ready_ = false; 18 | } 19 | if (capturing_) { 20 | if (pos_ < OSCILLOSCOPE_SIZE) { 21 | data_[pos_++] = sample_data; 22 | } else { 23 | pos_ = 0; 24 | capturing_ = false; 25 | } 26 | } 27 | } 28 | -------------------------------------------------------------------------------- /Firmware/MotorControl/oscilloscope.hpp: -------------------------------------------------------------------------------- 1 | #ifndef __OSCILLOSCOPE_HPP 2 | #define __OSCILLOSCOPE_HPP 3 | 4 | #include 5 | 6 | // if you use the oscilloscope feature you can bump up this value 7 | #define OSCILLOSCOPE_SIZE 4096 8 | 9 | class Oscilloscope : public ODriveIntf::OscilloscopeIntf { 10 | public: 11 | Oscilloscope(float* trigger_src, float trigger_threshold, float** data_src) 12 | : trigger_src_(trigger_src), trigger_threshold_(trigger_threshold), data_src_(data_src) {} 13 | 14 | float get_val(uint32_t index) override { 15 | return index < OSCILLOSCOPE_SIZE ? data_[index] : NAN; 16 | } 17 | 18 | void update(); 19 | 20 | const uint32_t size_ = OSCILLOSCOPE_SIZE; 21 | const float* trigger_src_; 22 | const float trigger_threshold_; 23 | float* const * data_src_; 24 | 25 | float data_[OSCILLOSCOPE_SIZE] = {0}; 26 | size_t pos_ = 0; 27 | bool ready_ = false; 28 | bool capturing_ = false; 29 | }; 30 | 31 | #endif // __OSCILLOSCOPE_HPP -------------------------------------------------------------------------------- /Firmware/MotorControl/pwm_input.hpp: -------------------------------------------------------------------------------- 1 | #ifndef __PWM_INPUT_HPP 2 | #define __PWM_INPUT_HPP 3 | 4 | #include 5 | #include 6 | 7 | class PwmInput { 8 | public: 9 | PwmInput(TIM_HandleTypeDef* htim, std::array gpios) 10 | : htim_(htim), gpios_(gpios) {} 11 | 12 | void init(); 13 | void on_capture(); 14 | 15 | private: 16 | void on_capture(int channel, uint32_t timestamp); 17 | 18 | TIM_HandleTypeDef* htim_; 19 | std::array gpios_; 20 | }; 21 | 22 | #endif // __PWM_INPUT_HPP -------------------------------------------------------------------------------- /Firmware/MotorControl/sensorless_estimator.hpp: -------------------------------------------------------------------------------- 1 | #ifndef __SENSORLESS_ESTIMATOR_HPP 2 | #define __SENSORLESS_ESTIMATOR_HPP 3 | 4 | #include "component.hpp" 5 | 6 | class SensorlessEstimator : public ODriveIntf::SensorlessEstimatorIntf { 7 | public: 8 | struct Config_t { 9 | float observer_gain = 1000.0f; // [rad/s] 10 | float pll_bandwidth = 1000.0f; // [rad/s] 11 | float pm_flux_linkage = 1.58e-3f; // [V / (rad/s)] { 5.51328895422 / ( * ) } 12 | }; 13 | 14 | void reset(); 15 | bool update(); 16 | 17 | Axis* axis_ = nullptr; // set by Axis constructor 18 | Config_t config_; 19 | 20 | // TODO: expose on protocol 21 | Error error_ = ERROR_NONE; 22 | float pll_pos_ = 0.0f; // [rad] 23 | float flux_state_[2] = {0.0f, 0.0f}; // [Vs] 24 | float V_alpha_beta_memory_[2] = {0.0f, 0.0f}; // [V] 25 | 26 | OutputPort phase_ = 0.0f; // [rad] 27 | OutputPort phase_vel_ = 0.0f; // [rad/s] 28 | OutputPort vel_estimate_ = 0.0f; // [turns/s] 29 | }; 30 | 31 | #endif /* __SENSORLESS_ESTIMATOR_HPP */ 32 | -------------------------------------------------------------------------------- /Firmware/MotorControl/task_timer.hpp: -------------------------------------------------------------------------------- 1 | #ifndef __TASK_TIMER_HPP 2 | #define __TASK_TIMER_HPP 3 | 4 | #include 5 | #include 6 | 7 | #define MEASURE_START_TIME 8 | #define MEASURE_END_TIME 9 | #define MEASURE_LENGTH 10 | #define MEASURE_MAX_LENGTH 11 | 12 | inline uint16_t sample_TIM13() { 13 | constexpr uint16_t clocks_per_cnt = (uint16_t)((float)TIM_1_8_CLOCK_HZ / (float)TIM_APB1_CLOCK_HZ); 14 | return clocks_per_cnt * TIM13->CNT; // TODO: Use a hw_config 15 | } 16 | 17 | struct TaskTimer { 18 | uint32_t start_time_ = 0; 19 | uint32_t end_time_ = 0; 20 | uint32_t length_ = 0; 21 | uint32_t max_length_ = 0; 22 | 23 | static bool enabled; 24 | 25 | uint32_t start() { 26 | return sample_TIM13(); 27 | } 28 | 29 | void stop(uint32_t start_time) { 30 | uint32_t end_time = sample_TIM13(); 31 | uint32_t length = end_time - start_time; 32 | 33 | if (enabled) { 34 | #ifdef MEASURE_START_TIME 35 | start_time_ = start_time; 36 | #endif 37 | #ifdef MEASURE_END_TIME 38 | end_time_ = end_time; 39 | #endif 40 | #ifdef MEASURE_LENGTH 41 | length_ = length; 42 | #endif 43 | } 44 | #ifdef MEASURE_MAX_LENGTH 45 | max_length_ = std::max(max_length_, length); 46 | #endif 47 | } 48 | }; 49 | 50 | struct TaskTimerContext { 51 | TaskTimerContext(const TaskTimerContext&) = delete; 52 | TaskTimerContext(const TaskTimerContext&&) = delete; 53 | void operator=(const TaskTimerContext&) = delete; 54 | void operator=(const TaskTimerContext&&) = delete; 55 | TaskTimerContext(TaskTimer& timer) : timer_(timer), start_time(timer.start()) {} 56 | ~TaskTimerContext() { timer_.stop(start_time); } 57 | 58 | TaskTimer& timer_; 59 | uint32_t start_time; 60 | bool exit_ = false; 61 | }; 62 | 63 | #define MEASURE_TIME(timer) for (TaskTimerContext __task_timer_ctx{timer}; !__task_timer_ctx.exit_; __task_timer_ctx.exit_ = true) 64 | 65 | #endif // __TASK_TIMER_HPP -------------------------------------------------------------------------------- /Firmware/MotorControl/thermistor.hpp: -------------------------------------------------------------------------------- 1 | #ifndef __THERMISTOR_HPP 2 | #define __THERMISTOR_HPP 3 | 4 | class Motor; // declared in motor.hpp 5 | 6 | #include "current_limiter.hpp" 7 | #include 8 | 9 | class ThermistorCurrentLimiter : public CurrentLimiter, public ODriveIntf::ThermistorCurrentLimiterIntf { 10 | public: 11 | virtual ~ThermistorCurrentLimiter() = default; 12 | 13 | ThermistorCurrentLimiter(uint16_t adc_channel, 14 | const float* const coefficients, 15 | size_t num_coeffs, 16 | const float& temp_limit_lower, 17 | const float& temp_limit_upper, 18 | const bool& enabled); 19 | 20 | void update(); 21 | bool do_checks(); 22 | float get_current_limit(float base_current_lim) const override; 23 | 24 | uint16_t adc_channel_; 25 | const float* const coefficients_; 26 | const size_t num_coeffs_; 27 | float temperature_ = NAN; // [°C] NaN while the ODrive is initializing. 28 | const float& temp_limit_lower_; 29 | const float& temp_limit_upper_; 30 | const bool& enabled_; 31 | Motor* motor_ = nullptr; // set by Motor::apply_config() 32 | std::array lpf_vals_ = { 0.0f }; 33 | }; 34 | 35 | class OnboardThermistorCurrentLimiter : public ThermistorCurrentLimiter, public ODriveIntf::OnboardThermistorCurrentLimiterIntf { 36 | public: 37 | struct Config_t { 38 | float temp_limit_lower = 100; 39 | float temp_limit_upper = 120; 40 | bool enabled = true; 41 | }; 42 | 43 | virtual ~OnboardThermistorCurrentLimiter() = default; 44 | OnboardThermistorCurrentLimiter(uint16_t adc_channel, const float* const coefficients, size_t num_coeffs); 45 | 46 | Config_t config_; 47 | }; 48 | 49 | class OffboardThermistorCurrentLimiter : public ThermistorCurrentLimiter, public ODriveIntf::OffboardThermistorCurrentLimiterIntf { 50 | public: 51 | static const size_t num_coeffs_ = 4; 52 | 53 | struct Config_t { 54 | float thermistor_poly_coeffs[num_coeffs_]; 55 | 56 | #if HW_VERSION_MAJOR == 3 57 | uint16_t gpio_pin = 4; 58 | #elif HW_VERSION_MAJOR == 4 59 | uint16_t gpio_pin = 2; 60 | #endif 61 | float temp_limit_lower = 100; 62 | float temp_limit_upper = 120; 63 | bool enabled = false; 64 | 65 | // custom setters 66 | OffboardThermistorCurrentLimiter* parent; 67 | void set_gpio_pin(uint16_t value) { gpio_pin = value; parent->decode_pin(); } 68 | }; 69 | 70 | virtual ~OffboardThermistorCurrentLimiter() = default; 71 | OffboardThermistorCurrentLimiter(); 72 | 73 | Config_t config_; 74 | 75 | bool apply_config(); 76 | 77 | private: 78 | void decode_pin(); 79 | }; 80 | 81 | #endif // __THERMISTOR_HPP 82 | -------------------------------------------------------------------------------- /Firmware/MotorControl/timer.hpp: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include 4 | template 5 | class Timer { 6 | public: 7 | void setTimeout(const T timeout) { 8 | timeout_ = timeout; 9 | } 10 | 11 | void setIncrement(const T increment) { 12 | increment_ = increment; 13 | } 14 | 15 | void start() { 16 | running_ = true; 17 | } 18 | 19 | void stop() { 20 | running_ = false; 21 | } 22 | 23 | // If the timer is started, increment the timer 24 | void update() { 25 | if (running_) 26 | timer_ = std::min(timer_ + increment_, timeout_); 27 | } 28 | 29 | void reset() { 30 | timer_ = static_cast(0); 31 | } 32 | 33 | bool expired() { 34 | return timer_ >= timeout_; 35 | } 36 | 37 | private: 38 | T timer_ = static_cast(0); // Current state 39 | T timeout_ = static_cast(0); // Time to count 40 | T increment_ = static_cast(0); // Amount to increment each time update() is called 41 | bool running_ = false; // update() only increments if runing_ is true 42 | }; 43 | -------------------------------------------------------------------------------- /Firmware/MotorControl/trapTraj.hpp: -------------------------------------------------------------------------------- 1 | #ifndef _TRAP_TRAJ_H 2 | #define _TRAP_TRAJ_H 3 | 4 | class TrapezoidalTrajectory { 5 | public: 6 | struct Config_t { 7 | float vel_limit = 2.0f; // [turn/s] 8 | float accel_limit = 0.5f; // [turn/s^2] 9 | float decel_limit = 0.5f; // [turn/s^2] 10 | }; 11 | 12 | struct Step_t { 13 | float Y; 14 | float Yd; 15 | float Ydd; 16 | }; 17 | 18 | bool planTrapezoidal(float Xf, float Xi, float Vi, 19 | float Vmax, float Amax, float Dmax); 20 | Step_t eval(float t); 21 | 22 | Axis* axis_ = nullptr; // set by Axis constructor 23 | Config_t config_; 24 | 25 | float Xi_; 26 | float Xf_; 27 | float Vi_; 28 | 29 | float Ar_; 30 | float Vr_; 31 | float Dr_; 32 | 33 | float Ta_; 34 | float Tv_; 35 | float Td_; 36 | float Tf_; 37 | 38 | float yAccel_; 39 | 40 | float t_; 41 | }; 42 | 43 | #endif -------------------------------------------------------------------------------- /Firmware/Tests/test_rotate.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | #include 4 | #include 5 | #include 6 | 7 | TEST_CASE("Rotate Axis State"){ 8 | std::array testArr = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9}; 9 | const int& currentVal = testArr.front(); 10 | CHECK(currentVal == testArr[0]); 11 | 12 | std::rotate(testArr.begin(), testArr.begin() + 1, testArr.end()); 13 | CHECK(currentVal == testArr[0]); 14 | CHECK(currentVal == 1); 15 | 16 | CHECK(testArr.back() == 0); 17 | 18 | std::rotate(testArr.begin(), testArr.begin() + 1, testArr.end()); 19 | CHECK(currentVal == testArr[0]); 20 | CHECK(currentVal == 2); 21 | CHECK(testArr.back() == 1); 22 | 23 | 24 | } 25 | 26 | TEST_CASE("Fill Test"){ 27 | std::array testArr = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9}; 28 | std::fill(testArr.begin(), testArr.end(), 6); 29 | for(const auto& val : testArr){ 30 | CHECK(val == 6); 31 | } 32 | } -------------------------------------------------------------------------------- /Firmware/Tests/test_timer.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include "MotorControl/timer.hpp" 3 | #include 4 | 5 | TEST_CASE_TEMPLATE("Timer2", T, float, int, char, uint32_t){ 6 | Timer myTimer; 7 | myTimer.setTimeout(10); 8 | myTimer.setIncrement(1); 9 | CHECK(!myTimer.expired()); 10 | 11 | myTimer.start(); 12 | CHECK(!myTimer.expired()); 13 | for(int i = 0; i < 9; ++i){ 14 | myTimer.update(); 15 | CHECK(!myTimer.expired()); 16 | } 17 | 18 | myTimer.update(); 19 | CHECK(myTimer.expired()); 20 | 21 | myTimer.stop(); 22 | CHECK(myTimer.expired()); 23 | 24 | myTimer.start(); 25 | CHECK(myTimer.expired()); 26 | 27 | myTimer.reset(); 28 | CHECK(!myTimer.expired()); 29 | } -------------------------------------------------------------------------------- /Firmware/ThirdParty/CMSIS/Device/ST/STM32F4xx/Include/stm32f4xx.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/Firmware/ThirdParty/CMSIS/Device/ST/STM32F4xx/Include/stm32f4xx.h -------------------------------------------------------------------------------- /Firmware/ThirdParty/CMSIS/Device/ST/STM32F7xx/Include/stm32f722xx.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/Firmware/ThirdParty/CMSIS/Device/ST/STM32F7xx/Include/stm32f722xx.h -------------------------------------------------------------------------------- /Firmware/ThirdParty/CMSIS/Device/ST/STM32F7xx/Include/stm32f7xx.h: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/Firmware/ThirdParty/CMSIS/Device/ST/STM32F7xx/Include/stm32f7xx.h -------------------------------------------------------------------------------- /Firmware/ThirdParty/CMSIS/Include/cmsis_version.h: -------------------------------------------------------------------------------- 1 | /**************************************************************************//** 2 | * @file cmsis_version.h 3 | * @brief CMSIS Core(M) Version definitions 4 | * @version V5.0.2 5 | * @date 19. April 2017 6 | ******************************************************************************/ 7 | /* 8 | * Copyright (c) 2009-2017 ARM Limited. All rights reserved. 9 | * 10 | * SPDX-License-Identifier: Apache-2.0 11 | * 12 | * Licensed under the Apache License, Version 2.0 (the License); you may 13 | * not use this file except in compliance with the License. 14 | * You may obtain a copy of the License at 15 | * 16 | * www.apache.org/licenses/LICENSE-2.0 17 | * 18 | * Unless required by applicable law or agreed to in writing, software 19 | * distributed under the License is distributed on an AS IS BASIS, WITHOUT 20 | * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 21 | * See the License for the specific language governing permissions and 22 | * limitations under the License. 23 | */ 24 | 25 | #if defined ( __ICCARM__ ) 26 | #pragma system_include /* treat file as system include file for MISRA check */ 27 | #elif defined (__clang__) 28 | #pragma clang system_header /* treat file as system include file */ 29 | #endif 30 | 31 | #ifndef __CMSIS_VERSION_H 32 | #define __CMSIS_VERSION_H 33 | 34 | /* CMSIS Version definitions */ 35 | #define __CM_CMSIS_VERSION_MAIN ( 5U) /*!< [31:16] CMSIS Core(M) main version */ 36 | #define __CM_CMSIS_VERSION_SUB ( 1U) /*!< [15:0] CMSIS Core(M) sub version */ 37 | #define __CM_CMSIS_VERSION ((__CM_CMSIS_VERSION_MAIN << 16U) | \ 38 | __CM_CMSIS_VERSION_SUB ) /*!< CMSIS Core(M) version number */ 39 | #endif 40 | -------------------------------------------------------------------------------- /Firmware/ThirdParty/CMSIS/Lib/GCC/libarm_cortexM4lf_math.a: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/Firmware/ThirdParty/CMSIS/Lib/GCC/libarm_cortexM4lf_math.a -------------------------------------------------------------------------------- /Firmware/ThirdParty/CMSIS/Lib/GCC/libarm_cortexM7lfsp_math.a: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/Firmware/ThirdParty/CMSIS/Lib/GCC/libarm_cortexM7lfsp_math.a -------------------------------------------------------------------------------- /Firmware/ThirdParty/STM32_USB_Device_Library/Core/Inc/usbd_ctlreq.h: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file usbd_req.h 4 | * @author MCD Application Team 5 | * @brief Header file for the usbd_req.c file 6 | ****************************************************************************** 7 | * @attention 8 | * 9 | *

© Copyright (c) 2015 STMicroelectronics. 10 | * All rights reserved.

11 | * 12 | * This software component is licensed by ST under Ultimate Liberty license 13 | * SLA0044, the "License"; You may not use this file except in compliance with 14 | * the License. You may obtain a copy of the License at: 15 | * www.st.com/SLA0044 16 | * 17 | ****************************************************************************** 18 | */ 19 | 20 | /* Define to prevent recursive inclusion -------------------------------------*/ 21 | #ifndef __USB_REQUEST_H 22 | #define __USB_REQUEST_H 23 | 24 | #ifdef __cplusplus 25 | extern "C" { 26 | #endif 27 | 28 | /* Includes ------------------------------------------------------------------*/ 29 | #include "usbd_def.h" 30 | 31 | 32 | /** @addtogroup STM32_USB_DEVICE_LIBRARY 33 | * @{ 34 | */ 35 | 36 | /** @defgroup USBD_REQ 37 | * @brief header file for the usbd_req.c file 38 | * @{ 39 | */ 40 | 41 | /** @defgroup USBD_REQ_Exported_Defines 42 | * @{ 43 | */ 44 | /** 45 | * @} 46 | */ 47 | 48 | 49 | /** @defgroup USBD_REQ_Exported_Types 50 | * @{ 51 | */ 52 | /** 53 | * @} 54 | */ 55 | 56 | 57 | 58 | /** @defgroup USBD_REQ_Exported_Macros 59 | * @{ 60 | */ 61 | /** 62 | * @} 63 | */ 64 | 65 | /** @defgroup USBD_REQ_Exported_Variables 66 | * @{ 67 | */ 68 | /** 69 | * @} 70 | */ 71 | 72 | /** @defgroup USBD_REQ_Exported_FunctionsPrototype 73 | * @{ 74 | */ 75 | 76 | USBD_StatusTypeDef USBD_StdDevReq(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req); 77 | USBD_StatusTypeDef USBD_StdItfReq(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req); 78 | USBD_StatusTypeDef USBD_StdEPReq(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req); 79 | 80 | void USBD_CtlError(USBD_HandleTypeDef *pdev, USBD_SetupReqTypedef *req); 81 | void USBD_ParseSetupRequest(USBD_SetupReqTypedef *req, uint8_t *pdata); 82 | void USBD_GetString(uint8_t *desc, uint8_t *unicode, uint16_t *len); 83 | 84 | /** 85 | * @} 86 | */ 87 | 88 | #ifdef __cplusplus 89 | } 90 | #endif 91 | 92 | #endif /* __USB_REQUEST_H */ 93 | 94 | /** 95 | * @} 96 | */ 97 | 98 | /** 99 | * @} 100 | */ 101 | 102 | 103 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ 104 | -------------------------------------------------------------------------------- /Firmware/Tupfile.ini: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/Firmware/Tupfile.ini -------------------------------------------------------------------------------- /Firmware/Tuprules.lua: -------------------------------------------------------------------------------- 1 | 2 | -- Prevent tup from running `Firmware/fibre-cpp/Tupfile.lua` when we run it in 3 | -- the `Firmware` folder. 4 | no_libfibre = tup.getconfig("BUILD_LIBFIBRE") != "true" 5 | -------------------------------------------------------------------------------- /Firmware/adctest.py: -------------------------------------------------------------------------------- 1 | 2 | import numpy as np 3 | import matplotlib.pyplot as plt 4 | 5 | adchist = [(0, 137477), 6 | (1, 98524), 7 | (2, 71744), 8 | (3, 60967), 9 | (4, 44372), 10 | (5, 46348), 11 | (6, 19944), 12 | (7, 10092), 13 | (8, 13713), 14 | (9, 11182), 15 | (10, 6903), 16 | (11, 4072), 17 | (12, 2642), 18 | (13, 968), 19 | (14, 296), 20 | (15, 166), 21 | (16, 17), 22 | (17, 2), 23 | (-1, 39662), 24 | (-2, 43502), 25 | (-3, 57596), 26 | (-4, 33915), 27 | (-5, 25611), 28 | (-6, 10880), 29 | (-7, 8237), 30 | (-8, 3518), 31 | (-9, 4789), 32 | (-10, 4689), 33 | (-11, 6345), 34 | (-12, 3901), 35 | (-13, 5781), 36 | (-14, 4803), 37 | (-15, 6428), 38 | (-16, 3563), 39 | (-17, 4478), 40 | (-18, 976), 41 | (-19, 491)] 42 | 43 | adchist.sort() 44 | 45 | adchist = np.array(adchist) 46 | 47 | plt.figure() 48 | plt.bar(adchist[:,0], adchist[:,1]) 49 | plt.show() -------------------------------------------------------------------------------- /Firmware/communication/ascii_protocol.hpp: -------------------------------------------------------------------------------- 1 | #ifndef __ASCII_PROTOCOL_HPP 2 | #define __ASCII_PROTOCOL_HPP 3 | 4 | #include 5 | #include 6 | 7 | #define MAX_LINE_LENGTH ((size_t)256) 8 | 9 | class AsciiProtocol { 10 | public: 11 | AsciiProtocol(fibre::AsyncStreamSource* rx_channel, fibre::AsyncStreamSink* tx_channel) 12 | : rx_channel_(rx_channel), sink_(*tx_channel) {} 13 | 14 | void start(); 15 | 16 | private: 17 | void cmd_set_position(char * pStr, bool use_checksum); 18 | void cmd_set_position_wl(char * pStr, bool use_checksum); 19 | void cmd_set_velocity(char * pStr, bool use_checksum); 20 | void cmd_set_torque(char * pStr, bool use_checksum); 21 | void cmd_set_trapezoid_trajectory(char * pStr, bool use_checksum); 22 | void cmd_get_feedback(char * pStr, bool use_checksum); 23 | void cmd_help(char * pStr, bool use_checksum); 24 | void cmd_info_dump(char * pStr, bool use_checksum); 25 | void cmd_system_ctrl(char * pStr, bool use_checksum); 26 | void cmd_read_property(char * pStr, bool use_checksum); 27 | void cmd_write_property(char * pStr, bool use_checksum); 28 | void cmd_update_axis_wdg(char * pStr, bool use_checksum); 29 | void cmd_unknown(char * pStr, bool use_checksum); 30 | void cmd_encoder(char * pStr, bool use_checksum); 31 | 32 | template void respond(bool include_checksum, const char * fmt, TArgs&& ... args); 33 | void process_line(fibre::cbufptr_t buffer); 34 | void on_write_finished(fibre::WriteResult result); 35 | void on_read_finished(fibre::ReadResult result); 36 | 37 | fibre::AsyncStreamSource* rx_channel_ = nullptr; 38 | uint8_t* rx_end_ = nullptr; // non-zero if an RX operation has finished but wasn't handled yet because the TX channel was busy 39 | 40 | uint8_t rx_buf_[MAX_LINE_LENGTH]; 41 | bool read_active_ = true; 42 | 43 | fibre::BufferedStreamSink<512> sink_; 44 | }; 45 | 46 | #endif // __ASCII_PROTOCOL_HPP 47 | -------------------------------------------------------------------------------- /Firmware/communication/can/canbus.hpp: -------------------------------------------------------------------------------- 1 | #ifndef __CANBUS_HPP 2 | #define __CANBUS_HPP 3 | 4 | #include "can_helpers.hpp" 5 | #include 6 | 7 | struct MsgIdFilterSpecs { 8 | std::variant id; 9 | uint32_t mask; 10 | }; 11 | 12 | class CanBusBase { 13 | public: 14 | typedef void(*on_can_message_cb_t)(void* ctx, const can_Message_t& message); 15 | struct CanSubscription {}; 16 | 17 | /** 18 | * @brief Sends the specified CAN message. 19 | * 20 | * @returns: true on success or false otherwise (e.g. if the send queue is 21 | * full). 22 | */ 23 | virtual bool send_message(const can_Message_t& message) = 0; 24 | 25 | /** 26 | * @brief Registers a callback that will be invoked for every incoming CAN 27 | * message that matches the filter. 28 | * 29 | * @param handle: On success this handle is set to an opaque pointer that 30 | * can be used to cancel the subscription. 31 | * 32 | * @returns: true on success or false otherwise (e.g. if the maximum number 33 | * of subscriptions has been reached). 34 | */ 35 | virtual bool subscribe(const MsgIdFilterSpecs& filter, on_can_message_cb_t callback, void* ctx, CanSubscription** handle) = 0; 36 | 37 | /** 38 | * @brief Deregisters a callback that was previously registered with subscribe(). 39 | */ 40 | virtual bool unsubscribe(CanSubscription* handle) = 0; 41 | }; 42 | 43 | #endif // __CANBUS_HPP -------------------------------------------------------------------------------- /Firmware/communication/can/odrive_can.hpp: -------------------------------------------------------------------------------- 1 | #ifndef __ODRIVE_CAN_HPP 2 | #define __ODRIVE_CAN_HPP 3 | 4 | #include 5 | 6 | #include "canbus.hpp" 7 | #include "can_simple.hpp" 8 | #include 9 | 10 | #define CAN_CLK_HZ (42000000) 11 | #define CAN_CLK_MHZ (42) 12 | 13 | // Anonymous enum for defining the most common CAN baud rates 14 | enum { 15 | CAN_BAUD_125K = 125000, 16 | CAN_BAUD_250K = 250000, 17 | CAN_BAUD_500K = 500000, 18 | CAN_BAUD_1000K = 1000000, 19 | CAN_BAUD_1M = 1000000 20 | }; 21 | 22 | class ODriveCAN : public CanBusBase, public ODriveIntf::CanIntf { 23 | public: 24 | struct Config_t { 25 | uint32_t baud_rate = CAN_BAUD_250K; 26 | Protocol protocol = PROTOCOL_SIMPLE; 27 | 28 | ODriveCAN* parent = nullptr; // set in apply_config() 29 | void set_baud_rate(uint32_t value) { parent->set_baud_rate(value); } 30 | }; 31 | 32 | ODriveCAN() {} 33 | 34 | bool apply_config(); 35 | bool start_server(CAN_HandleTypeDef* handle); 36 | 37 | Error error_ = ERROR_NONE; 38 | 39 | Config_t config_; 40 | CANSimple can_simple_{this}; 41 | 42 | osThreadId thread_id_; 43 | const uint32_t stack_size_ = 1024; // Bytes 44 | 45 | private: 46 | static const uint8_t kCanFifoNone = 0xff; 47 | 48 | struct ODriveCanSubscription : CanSubscription { 49 | uint8_t fifo = kCanFifoNone; 50 | on_can_message_cb_t callback; 51 | void* ctx; 52 | }; 53 | 54 | bool reinit(); 55 | void can_server_thread(); 56 | bool set_baud_rate(uint32_t baud_rate); 57 | void process_rx_fifo(uint32_t fifo); 58 | bool send_message(const can_Message_t& message) final; 59 | bool subscribe(const MsgIdFilterSpecs& filter, on_can_message_cb_t callback, void* ctx, CanSubscription** handle) final; 60 | bool unsubscribe(CanSubscription* handle) final; 61 | 62 | // Hardware supports at most 28 filters unless we do optimizations. For now 63 | // we don't need that many. 64 | std::array subscriptions_; 65 | CAN_HandleTypeDef *handle_ = nullptr; 66 | }; 67 | 68 | #endif // __ODRIVE_CAN_HPP 69 | -------------------------------------------------------------------------------- /Firmware/communication/communication.h: -------------------------------------------------------------------------------- 1 | #ifndef COMMANDS_H 2 | #define COMMANDS_H 3 | 4 | // TODO: resolve assert 5 | #define assert(expr) 6 | 7 | #ifdef __cplusplus 8 | 9 | #include 10 | #include 11 | 12 | extern "C" { 13 | #endif 14 | 15 | #include 16 | 17 | void init_communication(void); 18 | 19 | #ifdef __cplusplus 20 | } 21 | #endif 22 | 23 | #endif /* COMMANDS_H */ 24 | -------------------------------------------------------------------------------- /Firmware/communication/interface_can.hpp: -------------------------------------------------------------------------------- 1 | #ifndef __INTERFACE_CAN_HPP 2 | #define __INTERFACE_CAN_HPP 3 | 4 | //#include 5 | //#include "odrive_main.h" 6 | //#include "can_helpers.hpp" 7 | //#include 8 | //// Other protocol implementations here 9 | 10 | #endif 11 | -------------------------------------------------------------------------------- /Firmware/communication/interface_i2c.h: -------------------------------------------------------------------------------- 1 | #ifndef __INTERFACE_I2C_HPP 2 | #define __INTERFACE_I2C_HPP 3 | 4 | #ifdef __cplusplus 5 | extern "C" { 6 | #endif 7 | 8 | #include 9 | 10 | struct I2CStats_t { 11 | uint8_t addr; 12 | uint32_t addr_match_cnt; 13 | uint32_t rx_cnt; 14 | uint32_t error_cnt; 15 | }; 16 | 17 | extern I2CStats_t i2c_stats_; 18 | 19 | void start_i2c_server(void); 20 | 21 | #ifdef __cplusplus 22 | } 23 | #endif 24 | 25 | #endif // __INTERFACE_I2C_HPP 26 | -------------------------------------------------------------------------------- /Firmware/communication/interface_uart.h: -------------------------------------------------------------------------------- 1 | #ifndef __INTERFACE_UART_HPP 2 | #define __INTERFACE_UART_HPP 3 | 4 | 5 | #ifdef __cplusplus 6 | extern "C" { 7 | #endif 8 | 9 | #include 10 | #include "usart.h" 11 | 12 | extern osThreadId uart_thread; 13 | extern const uint32_t stack_size_uart_thread; 14 | 15 | void start_uart_server(UART_HandleTypeDef* huart); 16 | void uart_poll(void); 17 | 18 | #ifdef __cplusplus 19 | } 20 | #endif 21 | 22 | 23 | #ifdef __cplusplus 24 | #include 25 | extern fibre::BufferedStreamSink<64> uart0_stdout_sink; 26 | extern bool uart0_stdout_pending; 27 | #endif 28 | 29 | #endif // __INTERFACE_UART_HPP 30 | -------------------------------------------------------------------------------- /Firmware/communication/interface_usb.h: -------------------------------------------------------------------------------- 1 | #ifndef __INTERFACE_USB_HPP 2 | #define __INTERFACE_USB_HPP 3 | 4 | 5 | #ifdef __cplusplus 6 | extern "C" { 7 | #endif 8 | 9 | #include 10 | #include 11 | 12 | extern osThreadId usb_thread; 13 | extern const uint32_t stack_size_usb_thread; 14 | 15 | typedef struct { 16 | uint32_t rx_cnt; 17 | uint32_t tx_cnt; 18 | uint32_t tx_overrun_cnt; 19 | } USBStats_t; 20 | 21 | extern USBStats_t usb_stats_; 22 | 23 | void usb_rx_process_packet(uint8_t *buf, uint32_t len, uint8_t endpoint_pair); 24 | void start_usb_server(void); 25 | 26 | #ifdef __cplusplus 27 | } 28 | #endif 29 | 30 | 31 | #ifdef __cplusplus 32 | #include 33 | extern fibre::BufferedStreamSink<64> usb_cdc_stdout_sink; 34 | extern bool usb_cdc_stdout_pending; 35 | #endif 36 | 37 | #endif // __INTERFACE_USB_HPP 38 | -------------------------------------------------------------------------------- /Firmware/fibre-cpp/.gitignore: -------------------------------------------------------------------------------- 1 | /third_party 2 | build/ 3 | build-*/ 4 | /.tup 5 | -------------------------------------------------------------------------------- /Firmware/fibre-cpp/Makefile: -------------------------------------------------------------------------------- 1 | 2 | all: 3 | tup --no-environ-check build-local 4 | tup --no-environ-check build-wasm 5 | cp build-local/libfibre-* ../python/fibre/ 6 | cp build-wasm/libfibre-* ../js/ 7 | -------------------------------------------------------------------------------- /Firmware/fibre-cpp/channel_discoverer.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include 3 | #include 4 | #include 5 | #include 6 | 7 | using namespace fibre; 8 | 9 | bool ChannelDiscoverer::try_parse_key(const char* begin, const char* end, const char* key, const char** val_begin, const char** val_end) { 10 | ssize_t keylen = strlen(key); 11 | 12 | while (begin != end) { 13 | const char* next_delim = std::find(begin, end, ','); 14 | 15 | if ((next_delim - begin >= keylen) && (memcmp(begin, key, keylen) == 0)) { 16 | if (next_delim - begin == keylen) { 17 | // The key exists but has no value 18 | *val_begin = *val_end = next_delim; 19 | return true; 20 | } else if (begin[keylen] == '=') { 21 | *val_begin = begin + keylen + 1; 22 | *val_end = next_delim; 23 | return true; 24 | } 25 | } 26 | 27 | begin = std::min(next_delim + 1, end); 28 | } 29 | 30 | return false; // key not found 31 | } 32 | 33 | bool ChannelDiscoverer::try_parse_key(const char* begin, const char* end, const char* key, int* val) { 34 | const char* val_begin; 35 | const char* val_end; 36 | if (!try_parse_key(begin, end, key, &val_begin, &val_end)) { 37 | return false; 38 | } 39 | 40 | // Copy value to a null-terminated buffer 41 | char buf[val_end - val_begin + 1]; 42 | memcpy(buf, val_begin, val_end - val_begin); 43 | buf[val_end - val_begin] = 0; 44 | 45 | return sscanf(buf, "0x%x", val) == 1 46 | || sscanf(buf, "%d", val) == 1; 47 | } 48 | -------------------------------------------------------------------------------- /Firmware/fibre-cpp/configs/linux-amd64.config: -------------------------------------------------------------------------------- 1 | CONFIG_DEBUG=false 2 | CONFIG_STRICT=true 3 | CONFIG_CC="clang++" 4 | CONFIG_CFLAGS="-I$THIRD_PARTY./third_party/libusb-dev-armhf/usr/include/libusb-1.0" 5 | CONFIG_LDFLAGS="$THIRD_PARTY./third_party/libusb-amd64/lib/x86_64-linux-gnu/libusb-1.0.so.0.2.0" 6 | CONFIG_USE_PKGCONF=false 7 | -------------------------------------------------------------------------------- /Firmware/fibre-cpp/configs/linux-armhf.config: -------------------------------------------------------------------------------- 1 | CONFIG_DEBUG=false 2 | CONFIG_STRICT=true 3 | CONFIG_CC="arm-linux-gnueabihf-g++" 4 | CONFIG_CFLAGS="-I$THIRD_PARTY./third_party/libusb-dev-armhf/usr/include/libusb-1.0" 5 | CONFIG_LDFLAGS="-L$THIRD_PARTY./third_party/libstdc++-linux-armhf/usr/lib/gcc-cross/arm-linux-gnueabihf/10 $THIRD_PARTY./third_party/libusb-armhf/usr/lib/arm-linux-gnueabihf/libusb-1.0.so.0" 6 | CONFIG_USE_PKGCONF=false 7 | -------------------------------------------------------------------------------- /Firmware/fibre-cpp/configs/macos-x86.config: -------------------------------------------------------------------------------- 1 | CONFIG_DEBUG=false 2 | CONFIG_STRICT=true 3 | CONFIG_CC="LD_LIBRARY_PATH=/opt/osxcross/lib MACOSX_DEPLOYMENT_TARGET=10.9 /opt/osxcross/bin/o64-clang++" 4 | CONFIG_CFLAGS="-I$THIRD_PARTY./third_party/libusb-1.0.23/libusb -arch i386 -arch x86_64" 5 | CONFIG_LDFLAGS="$THIRD_PARTY./third_party/libusb-1.0.23/build-macos-amd64/libusb/.libs/libusb-1.0.a -framework CoreFoundation -framework IOKit" 6 | # not supported yet 7 | CONFIG_ENABLE_TCP_SERVER_BACKEND=false 8 | # not supported yet 9 | CONFIG_ENABLE_TCP_CLIENT_BACKEND=false 10 | CONFIG_USE_PKGCONF=false 11 | -------------------------------------------------------------------------------- /Firmware/fibre-cpp/configs/wasm.config: -------------------------------------------------------------------------------- 1 | CONFIG_DEBUG=true 2 | CONFIG_STRICT=true 3 | CONFIG_CC=/usr/lib/emscripten/em++ 4 | CONFIG_CFLAGS=-include emscripten.h -DFIBRE_PUBLIC=EMSCRIPTEN_KEEPALIVE -s RESERVED_FUNCTION_POINTERS=1 5 | CONFIG_LDFLAGS=-s EXPORT_ES6=1 -s MODULARIZE=1 -s USE_ES6_IMPORT_META=0 -s 'EXTRA_EXPORTED_RUNTIME_METHODS=[addFunction, stringToUTF8Array, UTF8ArrayToString, ENV]' 6 | CONFIG_USE_PKGCONF=false 7 | CONFIG_ENABLE_LIBUSB_BACKEND=false 8 | CONFIG_ENABLE_TCP_SERVER_BACKEND=false 9 | CONFIG_ENABLE_TCP_CLIENT_BACKEND=false 10 | -------------------------------------------------------------------------------- /Firmware/fibre-cpp/configs/windows-amd64.config: -------------------------------------------------------------------------------- 1 | CONFIG_DEBUG=false 2 | CONFIG_STRICT=true 3 | CONFIG_CC="x86_64-w64-mingw32-g++" 4 | CONFIG_CFLAGS="-I$THIRD_PARTY./third_party/libusb-windows/libusb-1.0.23/include/libusb-1.0" 5 | CONFIG_LDFLAGS="-static-libgcc $THIRD_PARTY./third_party/libusb-windows/libusb-1.0.23/MinGW64/static/libusb-1.0.a" 6 | # not supported yet 7 | CONFIG_ENABLE_TCP_SERVER_BACKEND=false 8 | # not supported yet 9 | CONFIG_ENABLE_TCP_CLIENT_BACKEND=false 10 | CONFIG_USE_PKGCONF=false 11 | -------------------------------------------------------------------------------- /Firmware/fibre-cpp/crc.hpp: -------------------------------------------------------------------------------- 1 | #ifndef __CRC_HPP 2 | #define __CRC_HPP 3 | 4 | #include 5 | #include 6 | 7 | // Calculates an arbitrary CRC for one byte. 8 | // Adapted from https://barrgroup.com/Embedded-Systems/How-To/CRC-Calculation-C-Code 9 | template 10 | static T calc_crc(T remainder, uint8_t value) { 11 | constexpr T BIT_WIDTH = (CHAR_BIT * sizeof(T)); 12 | constexpr T TOPBIT = ((T)1 << (BIT_WIDTH - 1)); 13 | 14 | // Bring the next byte into the remainder. 15 | remainder ^= (value << (BIT_WIDTH - 8)); 16 | 17 | // Perform modulo-2 division, a bit at a time. 18 | for (uint8_t bit = 8; bit; --bit) { 19 | if (remainder & TOPBIT) { 20 | remainder = (remainder << 1) ^ POLYNOMIAL; 21 | } else { 22 | remainder = (remainder << 1); 23 | } 24 | } 25 | 26 | return remainder; 27 | } 28 | 29 | template 30 | static T calc_crc(T remainder, const uint8_t* buffer, size_t length) { 31 | while (length--) 32 | remainder = calc_crc(remainder, *(buffer++)); 33 | return remainder; 34 | } 35 | 36 | template 37 | static uint8_t calc_crc8(uint8_t remainder, uint8_t value) { 38 | return calc_crc(remainder, value); 39 | } 40 | 41 | template 42 | static uint16_t calc_crc16(uint16_t remainder, uint8_t value) { 43 | return calc_crc(remainder, value); 44 | } 45 | 46 | template 47 | static uint8_t calc_crc8(uint8_t remainder, const uint8_t* buffer, size_t length) { 48 | return calc_crc(remainder, buffer, length); 49 | } 50 | 51 | template 52 | static uint16_t calc_crc16(uint16_t remainder, const uint8_t* buffer, size_t length) { 53 | return calc_crc(remainder, buffer, length); 54 | } 55 | 56 | #endif /* __CRC_HPP */ 57 | -------------------------------------------------------------------------------- /Firmware/fibre-cpp/function_stubs_template.j2: -------------------------------------------------------------------------------- 1 | /*[# This is the original template, thus the warning below does not apply to this file #] 2 | * ============================ WARNING ============================ 3 | * ==== This is an autogenerated file. ==== 4 | * ==== Any changes to this file will be lost when recompiling. ==== 5 | * ================================================================= 6 | * 7 | * This file contains serializing/deserializing stubs for the functions defined 8 | * in your interface file. 9 | * 10 | */ 11 | 12 | #include 13 | 14 | [% for intf in interfaces.values() %] 15 | [% for func in intf.functions.values() %] 16 | static inline bool [[func.fullname | to_snake_case]]([% for arg in func.in.values() %]std::optional<[[arg.type.c_name]]> in_[[arg.name]], [% endfor %][% for arg in func.out.values() %][[arg.type.c_name]]* out_[[arg.name]], [% endfor %]fibre::cbufptr_t* input_buffer, fibre::bufptr_t* output_buffer) { 17 | [%- if func.in %] 18 | bool success = [% for arg in func.in.values() %](in_[[arg.name]].has_value() || (in_[[arg.name]] = fibre::Codec<[[arg.type.c_name]]>::decode(input_buffer)).has_value()[% if arg.optional %] || true[% endif %])[% if not loop.last %] 19 | && [% endif %][% endfor %]; 20 | [%- else %] 21 | bool success = true; 22 | [%- endif %] 23 | if (!success) { 24 | return false; 25 | } 26 | [%- if func.implementation %] 27 | [% if func.out %]std::tuple<[% for arg in func.out.values() %][[arg.type.c_name]][[', ' if not loop.last]][% endfor %]> ret = [% endif %][[func.implementation]]([% for arg in func.in.values() %](*in_[[arg.name]][% if not arg.optional %])[% endif %][[', ' if not loop.last]][% endfor %]); 28 | [%- else %] 29 | [% if func.out %]std::tuple<[% for arg in func.out.values() %][[arg.type.c_name]][[', ' if not loop.last]][% endfor %]> ret = [% endif %](*in_[[(func.in.values() | first).name]])->[[func.name]]([% for arg in func.in.values() | skip_first %][% if not arg.optional %]*[% endif %]in_[[arg.name]][[', ' if not loop.last]][% endfor %]); 30 | [%- endif %] 31 | [%- if func.out %] 32 | return [% for arg in func.out.values() %]((out_[[arg.name]] && ((*out_[[arg.name]] = std::get<[[loop.index0]]>(ret)), true)) || fibre::Codec<[[arg.type.c_name]]>::encode(std::get<[[loop.index0]]>(ret), output_buffer))[% if not loop.last %] 33 | && [% endif %][% endfor %]; 34 | [%- else %] 35 | return true; 36 | [%- endif %] 37 | } 38 | [% endfor %] 39 | [% endfor %] 40 | 41 | -------------------------------------------------------------------------------- /Firmware/fibre-cpp/include/fibre/channel_discoverer.hpp: -------------------------------------------------------------------------------- 1 | #ifndef __FIBRE_CHANNEL_DISCOVERER 2 | #define __FIBRE_CHANNEL_DISCOVERER 3 | 4 | #include "async_stream.hpp" 5 | #include 6 | #include 7 | 8 | namespace fibre { 9 | 10 | struct ChannelDiscoveryResult { 11 | Status status; 12 | AsyncStreamSource* rx_channel; 13 | AsyncStreamSink* tx_channel; 14 | size_t mtu; 15 | }; 16 | 17 | struct ChannelDiscoveryContext {}; 18 | 19 | class Domain; // defined in fibre.hpp 20 | 21 | class ChannelDiscoverer { 22 | public: 23 | // TODO: maybe we should remove "handle" because a discovery can also be 24 | // uniquely identified by domain. 25 | virtual void start_channel_discovery( 26 | Domain* domain, 27 | const char* specs, size_t specs_len, 28 | ChannelDiscoveryContext** handle) = 0; 29 | virtual int stop_channel_discovery(ChannelDiscoveryContext* handle) = 0; 30 | 31 | protected: 32 | bool try_parse_key(const char* begin, const char* end, const char* key, const char** val_begin, const char** val_end); 33 | bool try_parse_key(const char* begin, const char* end, const char* key, int* val); 34 | }; 35 | 36 | } 37 | 38 | #endif // __FIBRE_CHANNEL_DISCOVERER -------------------------------------------------------------------------------- /Firmware/fibre-cpp/include/fibre/event_loop.hpp: -------------------------------------------------------------------------------- 1 | #ifndef __FIBRE_EVENT_LOOP_HPP 2 | #define __FIBRE_EVENT_LOOP_HPP 3 | 4 | #include "callback.hpp" 5 | #include 6 | 7 | namespace fibre { 8 | 9 | struct EventLoopTimer; 10 | 11 | /** 12 | * @brief Base class for event loops. 13 | * 14 | * Thread-safety: The public functions of this class except for post() must not 15 | * be assumed to be thread-safe. 16 | * Generally the functions of an event loop are only safe to be called from the 17 | * event loop's thread itself. 18 | */ 19 | class EventLoop { 20 | public: 21 | /** 22 | * @brief Registers a callback for immediate execution on the event loop 23 | * thread. 24 | * 25 | * This function must be thread-safe. 26 | */ 27 | virtual bool post(Callback callback) = 0; 28 | 29 | /** 30 | * @brief Registers the given file descriptor on this event loop. 31 | * 32 | * This function is only implemented on Unix-like systems. 33 | * 34 | * @param fd: A waitable Unix file descriptor on which to listen for events. 35 | * @param events: A bitfield that specifies the events to listen for. 36 | * For instance EPOLLIN or EPOLLOUT. 37 | * @param callback: The callback to invoke every time the event triggers. 38 | * A bitfield is passed to the callback to indicate which events were 39 | * triggered. This callback must remain valid until 40 | * deregister_event() is called for the same file descriptor. 41 | */ 42 | virtual bool register_event(int fd, uint32_t events, Callback callback) = 0; 43 | 44 | /** 45 | * @brief Deregisters the given event. 46 | * 47 | * Once this function returns, the associated callback will no longer be 48 | * invoked and its resources can be freed. 49 | */ 50 | virtual bool deregister_event(int fd) = 0; 51 | 52 | /** 53 | * @brief Registers a callback to be called at a later point in time. 54 | * 55 | * This returns an opaque handler which can be used to cancel the timer. 56 | * 57 | * @param delay: The delay from now in seconds. 58 | * TOOD: specify if OS sleep time is counted in. 59 | */ 60 | virtual struct EventLoopTimer* call_later(float delay, Callback callback) = 0; 61 | 62 | /** 63 | * @brief Cancels a timer which was previously started by call_later(). 64 | * 65 | * Must not be called after invokation of the callback has started. 66 | * This also means that cancel_timer() must not be called from within the 67 | * callback of the timer itself. 68 | */ 69 | virtual bool cancel_timer(EventLoopTimer* timer) = 0; 70 | }; 71 | 72 | } 73 | 74 | #endif // __FIBRE_EVENT_LOOP_HPP -------------------------------------------------------------------------------- /Firmware/fibre-cpp/include/fibre/status.hpp: -------------------------------------------------------------------------------- 1 | #ifndef __FIBRE_STATUS_HPP 2 | #define __FIBRE_STATUS_HPP 3 | 4 | namespace fibre { 5 | 6 | enum Status { 7 | kFibreOk, 8 | kFibreBusy, // 5 | #include 6 | #include 7 | #include 8 | #include 9 | //#include 10 | 11 | #include 12 | 13 | namespace fibre { 14 | 15 | /** 16 | * @brief Event loop based on the Linux-specific `epoll()` infrastructure. 17 | * 18 | * Thread safety: None of the public functions are thread-safe with respect to 19 | * each other. However they are thread safe with respect to the internal event 20 | * loop, that means register_event() and deregister_event() can be called from 21 | * within an event callback (which executes on the event loop thread), provided 22 | * those calls are properly synchronized with calls from other threads. 23 | */ 24 | class EpollEventLoop : public EventLoop { 25 | public: 26 | 27 | /** 28 | * @brief Starts the event loop on the current thread and places the 29 | * specified start callback on the event queue. 30 | * 31 | * The function returns when the event loop becomes empty or if a platform 32 | * error occurs. 33 | */ 34 | bool start(Callback on_started); 35 | 36 | bool post(Callback callback) final; 37 | bool register_event(int fd, uint32_t events, Callback callback) final; 38 | bool deregister_event(int fd) final; 39 | struct EventLoopTimer* call_later(float delay, Callback callback) final; 40 | bool cancel_timer(EventLoopTimer* timer) final; 41 | 42 | private: 43 | struct EventContext { 44 | //int fd; 45 | Callback callback; 46 | }; 47 | 48 | void run_callbacks(uint32_t); 49 | 50 | int epoll_fd_ = -1; 51 | int post_fd_ = -1; 52 | unsigned int iterations_ = 0; 53 | 54 | std::unordered_map context_map_; // required to deregister callbacks 55 | 56 | static const size_t max_triggered_events_ = 16; // max number of events that can be handled per iteration 57 | int n_triggered_events_ = 0; 58 | struct epoll_event triggered_events_[max_triggered_events_]; 59 | 60 | // List of callbacks that were submitted through post(). 61 | std::vector> pending_callbacks_; 62 | 63 | // Mutex to protect pending_callbacks_ 64 | std::mutex pending_callbacks_mutex_; 65 | }; 66 | 67 | } 68 | 69 | #endif // __FIBRE_LINUX_EVENT_LOOP_HPP -------------------------------------------------------------------------------- /Firmware/fibre-cpp/type_info_template.j2: -------------------------------------------------------------------------------- 1 | /*[# This is the original template, thus the warning below does not apply to this file #] 2 | * ============================ WARNING ============================ 3 | * ==== This is an autogenerated file. ==== 4 | * ==== Any changes to this file will be lost when recompiling. ==== 5 | * ================================================================= 6 | * 7 | * This file contains support functions for the ODrive ASCII protocol. 8 | * 9 | * TODO: might generalize this as an approach to runtime introspection. 10 | */ 11 | 12 | #include 13 | 14 | #pragma GCC push_options 15 | #pragma GCC optimize ("s") 16 | 17 | [% for intf in interfaces.values() %][% if not intf.builtin %] 18 | template 19 | struct [[intf.fullname | to_pascal_case]]TypeInfo : TypeInfo { 20 | using TypeInfo::TypeInfo; 21 | static const PropertyInfo property_table[]; 22 | static const [[intf.fullname | to_pascal_case]]TypeInfo singleton; 23 | static Introspectable make_introspectable(T& obj) { return TypeInfo::make_introspectable(&obj, &singleton); } 24 | 25 | introspectable_storage_t get_child(introspectable_storage_t obj, size_t idx) const override { 26 | T* ptr = *(T**)&obj; 27 | introspectable_storage_t res; 28 | switch (idx) { 29 | [%- for property in intf.get_all_attributes().values() %] 30 | case [[loop.index0]]: *(decltype([[intf.c_name]]::get_[[property.name]](std::declval()))*)(&res) = [[intf.c_name]]::get_[[property.name]](ptr); break; 31 | [%- endfor %] 32 | } 33 | return res; 34 | } 35 | }; 36 | [% endif %][% endfor %] 37 | 38 | [% for intf in interfaces.values() %][% if not intf.builtin %] 39 | template 40 | const PropertyInfo [[intf.fullname | to_pascal_case]]TypeInfo::property_table[] = { 41 | [%- for property in intf.get_all_attributes().values() %] 42 | {"[[property.name]]", &[[(property.type.purename or property.type.fullname) | to_pascal_case]]TypeInfo()))>>::singleton}, 43 | [%- endfor %] 44 | }; 45 | template 46 | const [[intf.fullname | to_pascal_case]]TypeInfo [[intf.fullname | to_pascal_case]]TypeInfo::singleton{[[intf.fullname | to_pascal_case]]TypeInfo::property_table, sizeof([[intf.fullname | to_pascal_case]]TypeInfo::property_table) / sizeof([[intf.fullname | to_pascal_case]]TypeInfo::property_table[0])}; 47 | 48 | [% endif %][% endfor %] 49 | 50 | #pragma GCC pop_options 51 | -------------------------------------------------------------------------------- /Firmware/freertos_vars.h: -------------------------------------------------------------------------------- 1 | /* Define to prevent recursive inclusion -------------------------------------*/ 2 | #ifndef __FREERTOS_H 3 | #define __FREERTOS_H 4 | 5 | // TODO: this header is weird. Move these declarations to somewhere else. 6 | 7 | // List of semaphores 8 | extern osSemaphoreId sem_usb_irq; 9 | extern osMessageQId uart_event_queue; 10 | extern osMessageQId usb_event_queue; 11 | extern osSemaphoreId sem_can; 12 | 13 | extern osThreadId defaultTaskHandle; 14 | extern const uint32_t stack_size_default_task; 15 | 16 | #endif /* __FREERTOS_H */ -------------------------------------------------------------------------------- /Firmware/interface_generator_stub.py: -------------------------------------------------------------------------------- 1 | #!/bin/python3 2 | 3 | import sys 4 | import os 5 | 6 | try: 7 | path = os.path.join(os.path.dirname(os.path.dirname(os.path.realpath(__file__))), 'tools', 'fibre-tools', 'interface_generator.py') 8 | exec(compile(open(path).read(), path, 'exec')) 9 | except ImportError as ex: 10 | print(str(ex), file=sys.stderr) 11 | print("Note that there are new compile-time dependencies since around v0.5.1.", file=sys.stderr) 12 | print("Check out https://github.com/odriverobotics/ODrive/blob/devel/docs/developer-guide.md#prerequisites for details.", file=sys.stderr) 13 | exit(1) 14 | -------------------------------------------------------------------------------- /Firmware/motor_timing.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/Firmware/motor_timing.jpg -------------------------------------------------------------------------------- /Firmware/syscalls.c: -------------------------------------------------------------------------------- 1 | /** 2 | ****************************************************************************** 3 | * @file : syscalls.c 4 | * @brief : This file implements printf functionality 5 | ****************************************************************************** 6 | */ 7 | 8 | #include 9 | #include 10 | 11 | 12 | //int _read(int file, char *data, int len) {} 13 | //int _close(int file) {} 14 | //int _lseek(int file, int ptr, int dir) {} 15 | //int _fstat(int file, struct stat *st) {} 16 | //int _isatty(int file) {} 17 | 18 | extern char _end; // provided by the linker script: it's end of statically allocated section, which is where the heap starts. 19 | extern char _heap_end_max; // provided by the linker script 20 | void* _end_ptr = &_end; 21 | void* _heap_end_max_ptr = &_heap_end_max; 22 | void* heap_end_ptr = 0; 23 | 24 | /* @brief Increments the program break (aka heap end) 25 | * 26 | * This is called internally by malloc once it runs out 27 | * of heap space. Malloc might expect a contiguous heap, 28 | * so we don't call the FreeRTOS pvPortMalloc here. 29 | * If this function returns -1, malloc will return NULL. 30 | * Note that if this function returns NULL, malloc does not 31 | * consider this as an error and will return the pointer 0x8. 32 | * 33 | * You should still be careful with using malloc though, 34 | * as it does not guarantee thread safety. 35 | * 36 | * @return A pointer to the newly allocated block on success 37 | * or -1 otherwise. 38 | */ 39 | intptr_t _sbrk(size_t size) { 40 | intptr_t ptr; 41 | { 42 | uint32_t mask = cpu_enter_critical(); 43 | if (!heap_end_ptr) 44 | heap_end_ptr = _end_ptr; 45 | if (heap_end_ptr + size > _heap_end_max_ptr) { 46 | ptr = -1; 47 | } else { 48 | ptr = (intptr_t)heap_end_ptr; 49 | heap_end_ptr += size; 50 | } 51 | cpu_exit_critical(mask); 52 | } 53 | return ptr; 54 | } 55 | 56 | // _write is defined in communication.cpp 57 | 58 | 59 | -------------------------------------------------------------------------------- /Firmware/timing_diagram_v3.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/Firmware/timing_diagram_v3.png -------------------------------------------------------------------------------- /Firmware/tup.config.default: -------------------------------------------------------------------------------- 1 | # Copy this file to tup.config and adapt it to your needs 2 | # make sure this fits your board 3 | #CONFIG_BOARD_VERSION=v3.6-56V 4 | CONFIG_DEBUG=false 5 | CONFIG_DOCTEST=false 6 | CONFIG_USE_LTO=false 7 | 8 | # Path to the ARM compiler /bin folder (optional) 9 | #CONFIG_ARM_COMPILER_PATH=C:/Tools/ARM/9-2019-q4-major/bin 10 | 11 | # Uncomment this to error on compilation warnings 12 | #CONFIG_STRICT=true 13 | -------------------------------------------------------------------------------- /GUI/.gitignore: -------------------------------------------------------------------------------- 1 | .DS_Store 2 | node_modules 3 | /dist 4 | 5 | # local env files 6 | .env.local 7 | .env.*.local 8 | 9 | # Log files 10 | npm-debug.log* 11 | yarn-debug.log* 12 | yarn-error.log* 13 | pnpm-debug.log* 14 | 15 | # Editor directories and files 16 | .idea 17 | .vscode 18 | *.suo 19 | *.ntvs* 20 | *.njsproj 21 | *.sln 22 | *.sw? 23 | 24 | #Electron-builder output 25 | /dist_electron 26 | 27 | #Electron icon generator output 28 | /build -------------------------------------------------------------------------------- /GUI/LICENSE.md: -------------------------------------------------------------------------------- 1 | MIT License 2 | 3 | Copyright (c) 2020 ODrive Robotics 4 | 5 | Permission is hereby granted, free of charge, to any person obtaining a copy 6 | of this software and associated documentation files (the "Software"), to deal 7 | in the Software without restriction, including without limitation the rights 8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 9 | copies of the Software, and to permit persons to whom the Software is 10 | furnished to do so, subject to the following conditions: 11 | 12 | The above copyright notice and this permission notice shall be included in all 13 | copies or substantial portions of the Software. 14 | 15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 21 | SOFTWARE. 22 | -------------------------------------------------------------------------------- /GUI/README.md: -------------------------------------------------------------------------------- 1 | # odrive_gui 2 | 3 | Python requirements: `pip install flask flask_socketio flask_cors odrive` 4 | 5 | If the default odrive python package is not desired, the path to the modules can be passed as command line arguments. 6 | 7 | example on windows 10: 8 | ``` 9 | ./odrive_gui_win.exe C:/Users//ODrive/tools C:/Users//ODrive/Firmware 10 | ``` 11 | 12 | The first argument is for your local version of odrivetool, the second is for fibre. 13 | 14 | ## Development and testing instructions 15 | 16 | ### Project setup 17 | ``` 18 | npm install 19 | ``` 20 | 21 | ### Compiles and hot-reloads for development 22 | ``` 23 | npm run serve 24 | ``` 25 | 26 | ### Lints and fixes files 27 | ``` 28 | npm run lint 29 | ``` 30 | 31 | ### Serve electron version of GUI 32 | ``` 33 | npm run electron:serve 34 | ``` 35 | 36 | ### Package electron app into executable 37 | ``` 38 | npm run electron:build 39 | ``` 40 | 41 | ### Build electron app for all platforms 42 | ``` 43 | npm run electron:build -- -mwl 44 | ``` 45 | 46 | ### Running from source 47 | On the devel git branch, there may be unreleased changes to dependencies like fibre or the ODrive enumerations. 48 | Use this command to launch the GUI with the dependencies from the repo: 49 | ``` 50 | npm run electron:serve -- ../tools/ 51 | ``` 52 | 53 | ### Building for rpi and potentially other ARM platform devices 54 | 55 | PhantomJS is required as a dependency, so it must be installed first: 56 | ``` 57 | sudo apt install phantomjs 58 | ``` 59 | 60 | After it is installed, `npm run electron:build` can be used to build the AppImage for ARM 61 | 62 | ### Customize configuration 63 | See [Configuration Reference](https://cli.vuejs.org/config/). 64 | -------------------------------------------------------------------------------- /GUI/babel.config.js: -------------------------------------------------------------------------------- 1 | module.exports = { 2 | presets: [ 3 | '@vue/cli-plugin-babel/preset' 4 | ] 5 | } 6 | -------------------------------------------------------------------------------- /GUI/fibre-js/example.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/GUI/fibre-js/example.gif -------------------------------------------------------------------------------- /GUI/fibre-js/example.html: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | fibre-js Test 6 | 7 | 8 |

not connected

9 | 10 | 27 | 28 | -------------------------------------------------------------------------------- /GUI/fibre-js/libfibre-wasm.wasm: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/GUI/fibre-js/libfibre-wasm.wasm -------------------------------------------------------------------------------- /GUI/fibre-js/multidevice_example.html: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | WebAssembly Test 6 | 11 | 12 | 13 |
loading...
14 | 15 | 45 | 46 | 47 | 48 | -------------------------------------------------------------------------------- /GUI/fibre-js/package.json: -------------------------------------------------------------------------------- 1 | { 2 | "name": "fibre-js", 3 | "version": "0.1.0", 4 | "eslintConfig": { 5 | "rules": { 6 | "no-empty": "off", 7 | "no-unused-vars": "off", 8 | "no-undef": "off", 9 | "no-constant-condition": "off", 10 | "no-extra-semi": "off", 11 | "no-async-promise-executor": "off", 12 | "no-redeclare": "off", 13 | "no-prototype-builtins": "off", 14 | "no-global-assign": "off", 15 | "no-useless-escape": "off", 16 | "no-useless-catch": "off" 17 | } 18 | } 19 | } 20 | -------------------------------------------------------------------------------- /GUI/package.json: -------------------------------------------------------------------------------- 1 | { 2 | "name": "ODriveGUI", 3 | "version": "0.1.0", 4 | "private": true, 5 | "scripts": { 6 | "serve": "vue-cli-service serve", 7 | "build": "vue-cli-service build", 8 | "lint": "vue-cli-service lint", 9 | "enumGenerate": "node scripts/enumGenerate.js", 10 | "preelectron:build": "electron-icon-builder --input=./public/icon.png --output=build --flatten && npm run enumGenerate", 11 | "electron:build": "vue-cli-service electron:build", 12 | "preelectron:serve": "npm run enumGenerate", 13 | "electron:serve": "vue-cli-service electron:serve", 14 | "postinstall": "electron-builder install-app-deps", 15 | "postuninstall": "electron-builder install-app-deps", 16 | "electron:generate-icons": "electron-icon-builder --input=./public/icon.png --output=build --flatten" 17 | }, 18 | "main": "background.js", 19 | "dependencies": { 20 | "chart.js": "^2.9.3", 21 | "chartjs-plugin-streaming": "^1.8.0", 22 | "core-js": "^3.6.5", 23 | "electron": "^15.5.5", 24 | "file-saver": "^2.0.2", 25 | "socket.io-client": "^3.0.4", 26 | "typeface-roboto": "0.0.75", 27 | "uuid": "^8.2.0", 28 | "vue": "^2.6.11", 29 | "vue-chartjs": "^3.5.0", 30 | "vue-context": "^5.2.0", 31 | "vue-directive-tooltip": "^1.6.3", 32 | "vue-json-component": "^0.4.1", 33 | "vue-slider-component": "^3.2.11", 34 | "vuex": "^3.5.1" 35 | }, 36 | "devDependencies": { 37 | "@vue/cli-plugin-babel": "~4.4.0", 38 | "@vue/cli-plugin-eslint": "~4.4.0", 39 | "@vue/cli-plugin-router": "^4.4.6", 40 | "@vue/cli-service": "~4.4.0", 41 | "babel-eslint": "^10.1.0", 42 | "electron": "^15.5.5", 43 | "electron-devtools-installer": "^3.1.0", 44 | "electron-icon-builder": "^1.0.2", 45 | "eslint": "^6.7.2", 46 | "eslint-plugin-vue": "^6.2.2", 47 | "vue-cli-plugin-electron-builder": "~2.0.0-rc.4", 48 | "vue-cli-plugin-yaml": "^1.0.2", 49 | "vue-template-compiler": "^2.6.11" 50 | }, 51 | "eslintConfig": { 52 | "root": true, 53 | "env": { 54 | "node": true 55 | }, 56 | "extends": [ 57 | "plugin:vue/essential", 58 | "eslint:recommended" 59 | ], 60 | "parserOptions": { 61 | "parser": "babel-eslint" 62 | }, 63 | "rules": {} 64 | }, 65 | "browserslist": [ 66 | "> 1%", 67 | "last 2 versions", 68 | "not dead" 69 | ] 70 | } 71 | -------------------------------------------------------------------------------- /GUI/public/favicon.ico: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/GUI/public/favicon.ico -------------------------------------------------------------------------------- /GUI/public/icon.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/GUI/public/icon.png -------------------------------------------------------------------------------- /GUI/public/index.html: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | <%= htmlWebpackPlugin.options.title %> 9 | 10 | 11 | 14 |
15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /GUI/scripts/enumGenerate.js: -------------------------------------------------------------------------------- 1 | const fs = require('fs'); 2 | const path = require('path'); 3 | 4 | 5 | fs.readFile(path.resolve(__dirname,'..','..','tools','odrive','enums.py'), 'utf8', function(err, data) { 6 | if (err) throw err; 7 | let enumsString = data; 8 | let lines = enumsString.split(process.platform == 'win32' ? '\r\n' : '\n'); 9 | let enums = {}; 10 | for (const line of lines) { 11 | if (line != '' && line[0] != '#') { 12 | let name; 13 | let value; 14 | name = line.split('=')[0]; 15 | value = line.split('=')[1]; 16 | enums[name.trim()] = parseInt(value.trim()); 17 | } 18 | } 19 | fs.writeFile(path.resolve(__dirname, '../src/assets/odriveEnums.json'), JSON.stringify(enums, null, 4), function(err) { 20 | if (err) throw err; 21 | }); 22 | console.log('Wrote ODrive enums to GUI/src/assets/odriveEnums.json'); 23 | }); 24 | -------------------------------------------------------------------------------- /GUI/src/assets/images/24v_300x300.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/GUI/src/assets/images/24v_300x300.png -------------------------------------------------------------------------------- /GUI/src/assets/images/56v_300x300.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/GUI/src/assets/images/56v_300x300.png -------------------------------------------------------------------------------- /GUI/src/assets/images/D5065_300x300.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/GUI/src/assets/images/D5065_300x300.png -------------------------------------------------------------------------------- /GUI/src/assets/images/D6374_300x300.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/GUI/src/assets/images/D6374_300x300.png -------------------------------------------------------------------------------- /GUI/src/assets/images/M0M1_300x300.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/GUI/src/assets/images/M0M1_300x300.png -------------------------------------------------------------------------------- /GUI/src/assets/images/M0_300x300.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/GUI/src/assets/images/M0_300x300.png -------------------------------------------------------------------------------- /GUI/src/assets/images/M1_300x300.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/GUI/src/assets/images/M1_300x300.png -------------------------------------------------------------------------------- /GUI/src/assets/images/amt102-v_300x300.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/GUI/src/assets/images/amt102-v_300x300.png -------------------------------------------------------------------------------- /GUI/src/assets/images/hall_effect_300x300.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/GUI/src/assets/images/hall_effect_300x300.png -------------------------------------------------------------------------------- /GUI/src/assets/images/temp.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/GUI/src/assets/images/temp.png -------------------------------------------------------------------------------- /GUI/src/assets/odrive_logo.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/GUI/src/assets/odrive_logo.png -------------------------------------------------------------------------------- /GUI/src/assets/styles/style.css: -------------------------------------------------------------------------------- 1 | .card { 2 | padding: 10px; 3 | margin: 10px; 4 | background-color: #fff; 5 | box-shadow: 0 4px 8px 0 rgba(0, 0, 0, 0.4); 6 | } 7 | 8 | .close-button { 9 | font-weight: bold; 10 | cursor: pointer; 11 | padding: 0 5px; 12 | margin-right: 10px; 13 | border: 1px solid black; 14 | } 15 | 16 | .close-button:active { 17 | background-color: var(--bg-color); 18 | } 19 | 20 | .choice-inactive { 21 | background-color: var(--bg-color); 22 | color: grey; 23 | } -------------------------------------------------------------------------------- /GUI/src/assets/styles/vars.css: -------------------------------------------------------------------------------- 1 | :root { 2 | --bg-color: rgb(235, 235, 235); 3 | --fg-color: #fff; 4 | --top-height: 39px; 5 | --bottom-height: 29px; 6 | } -------------------------------------------------------------------------------- /GUI/src/assets/wizard/configTemplate.json: -------------------------------------------------------------------------------- 1 | { 2 | "config": { 3 | "brake_resistance": null 4 | }, 5 | "axis0": { 6 | "motor": { 7 | "config": { 8 | "pole_pairs": null, 9 | "phase_resistance": null, 10 | "phase_inductance": null, 11 | "motor_type": null, 12 | "current_lim": null, 13 | "torque_constant": null 14 | } 15 | }, 16 | "encoder": { 17 | "config": { 18 | "mode": null, 19 | "use_index": null, 20 | "cpr": null, 21 | "calib_scan_distance": null, 22 | "abs_spi_cs_gpio_pin": null 23 | } 24 | }, 25 | "controller": { 26 | "config": { 27 | "input_mode": null, 28 | "control_mode": null, 29 | "vel_limit": null, 30 | "inertia": null 31 | } 32 | }, 33 | "trap_traj": { 34 | "config": { 35 | "vel_limit": null, 36 | "accel_limit": null, 37 | "decel_limit": null 38 | } 39 | } 40 | }, 41 | "axis1": { 42 | "motor": { 43 | "config": { 44 | "pole_pairs": null, 45 | "phase_resistance": null, 46 | "phase_inductance": null, 47 | "motor_type": null, 48 | "current_lim": null, 49 | "torque_constant": null 50 | } 51 | }, 52 | "encoder": { 53 | "config": { 54 | "mode": null, 55 | "use_index": null, 56 | "cpr": null, 57 | "calib_scan_distance": null, 58 | "abs_spi_cs_gpio_pin": null 59 | } 60 | }, 61 | "controller": { 62 | "config": { 63 | "input_mode": null, 64 | "control_mode": null, 65 | "vel_limit": null, 66 | "inertia": null 67 | } 68 | }, 69 | "trap_traj": { 70 | "config": { 71 | "vel_limit": null, 72 | "accel_limit": null, 73 | "decel_limit": null 74 | } 75 | } 76 | } 77 | } -------------------------------------------------------------------------------- /GUI/src/comms/socketio.js: -------------------------------------------------------------------------------- 1 | import io from 'socket.io-client'; 2 | 3 | let socket = undefined; 4 | let url = 'https://0.0.0.0:8080'; 5 | 6 | function initSocket(url) { 7 | socket = io(url); 8 | } 9 | 10 | export function setUrl(path) { 11 | if (socket) { 12 | socket.close(); 13 | socket = undefined; 14 | } 15 | url = path; 16 | initSocket(url); 17 | } 18 | 19 | export function closeSocket() { 20 | socket.close(); 21 | socket = undefined; 22 | } 23 | 24 | export function addEventListener(event) { 25 | if (!socket) { 26 | initSocket(url); 27 | } 28 | socket.on(event.type, event.callback); 29 | } 30 | 31 | export function sendEvent(event) { 32 | socket.emit(event.type, event.data); 33 | } -------------------------------------------------------------------------------- /GUI/src/components/actions/ActionEnum.vue: -------------------------------------------------------------------------------- 1 | 15 | 16 | 64 | 65 | -------------------------------------------------------------------------------- /GUI/src/components/clearErrors.vue: -------------------------------------------------------------------------------- 1 | 6 | 7 | 33 | 34 | -------------------------------------------------------------------------------- /GUI/src/components/controls/CtrlBoolean.vue: -------------------------------------------------------------------------------- 1 | 18 | 19 | 71 | 72 | -------------------------------------------------------------------------------- /GUI/src/components/controls/CtrlFunction.vue: -------------------------------------------------------------------------------- 1 | 7 | 8 | 40 | 41 | -------------------------------------------------------------------------------- /GUI/src/components/plots/LineChart.js: -------------------------------------------------------------------------------- 1 | import { Line, mixins } from 'vue-chartjs'; 2 | import 'chartjs-plugin-streaming'; 3 | const { reactiveProp } = mixins; 4 | 5 | export default { 6 | extends: Line, 7 | mixins: [reactiveProp], 8 | props: ['options'], 9 | mounted () { 10 | // this.chartData is created in the mixin. 11 | // If you want to pass options please create a local options object 12 | this.renderChart(this.chartData, this.options) 13 | } 14 | } -------------------------------------------------------------------------------- /GUI/src/components/wizard/choices/wizardBrake.vue: -------------------------------------------------------------------------------- 1 | 10 | 11 | 58 | 59 | -------------------------------------------------------------------------------- /GUI/src/components/wizard/choices/wizardChoice.vue: -------------------------------------------------------------------------------- 1 | 8 | 9 | 39 | 40 | -------------------------------------------------------------------------------- /GUI/src/components/wizard/choices/wizardEncoderIncremental.vue: -------------------------------------------------------------------------------- 1 | 10 | 11 | 67 | 68 | -------------------------------------------------------------------------------- /GUI/src/components/wizard/choices/wizardEncoderIncrementalIndex.vue: -------------------------------------------------------------------------------- 1 | 10 | 11 | 68 | 69 | -------------------------------------------------------------------------------- /GUI/src/components/wizard/page_components/wizardCalStatus.vue: -------------------------------------------------------------------------------- 1 | 11 | 12 | 32 | 33 | -------------------------------------------------------------------------------- /GUI/src/components/wizard/page_components/wizardEncoderCal.vue: -------------------------------------------------------------------------------- 1 | 6 | 7 | 28 | 29 | -------------------------------------------------------------------------------- /GUI/src/components/wizard/page_components/wizardMotorCal.vue: -------------------------------------------------------------------------------- 1 | 6 | 7 | 29 | 30 | -------------------------------------------------------------------------------- /GUI/src/main.js: -------------------------------------------------------------------------------- 1 | import Vue from 'vue' 2 | import App from './App.vue' 3 | import store from './store' 4 | import Tooltip from 'vue-directive-tooltip'; 5 | import 'vue-directive-tooltip/dist/vueDirectiveTooltip.css'; 6 | import 'typeface-roboto/index.css'; 7 | 8 | Vue.config.productionTip = false 9 | Vue.use(Tooltip); 10 | 11 | new Vue({ 12 | store, 13 | render: h => h(App) 14 | }).$mount('#app') 15 | -------------------------------------------------------------------------------- /GUI/src/preload.js: -------------------------------------------------------------------------------- 1 | import { ipcRenderer } from 'electron' 2 | window.ipcRenderer = ipcRenderer -------------------------------------------------------------------------------- /GUI/vue.config.js: -------------------------------------------------------------------------------- 1 | // this file is used for configuring electron-builder 2 | 3 | module.exports = { 4 | pluginOptions: { 5 | electronBuilder: { 6 | preload: 'src/preload.js', 7 | //nodeIntegration: true, 8 | builderOptions: { 9 | "productName": "ODriveGUI", 10 | "asar": false, 11 | "extraResources": "server", 12 | "artifactName": "${name}.${ext}", 13 | "win" : { 14 | "target" : [ 15 | { 16 | "target": "portable", 17 | } 18 | ] 19 | }, 20 | "linux" : { 21 | "target" : [ 22 | { 23 | "target": "AppImage", 24 | } 25 | ] 26 | } 27 | }, 28 | //mainProcessArgs: ['C:/Users/pajoh/Desktop/ODrive_work/ODrive/tools', 'C:/Users/pajoh/Desktop/ODrive_work/ODrive/Firmware'] 29 | } 30 | } 31 | } -------------------------------------------------------------------------------- /LICENSE.md: -------------------------------------------------------------------------------- 1 | MIT License 2 | 3 | Copyright (c) 2016-2018 ODrive Robotics 4 | 5 | Permission is hereby granted, free of charge, to any person obtaining a copy 6 | of this software and associated documentation files (the "Software"), to deal 7 | in the Software without restriction, including without limitation the rights 8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 9 | copies of the Software, and to permit persons to whom the Software is 10 | furnished to do so, subject to the following conditions: 11 | 12 | The above copyright notice and this permission notice shall be included in all 13 | copies or substantial portions of the Software. 14 | 15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 21 | SOFTWARE. 22 | -------------------------------------------------------------------------------- /ODrive_Workspace.code-workspace: -------------------------------------------------------------------------------- 1 | { 2 | "folders": [ 3 | { 4 | "path": "Firmware" 5 | }, 6 | { 7 | "path": "tools" 8 | }, 9 | { 10 | "path": "docs" 11 | }, 12 | { 13 | "path": "analysis" 14 | }, 15 | { 16 | "path": "Arduino" 17 | }, 18 | { 19 | "path": "GUI" 20 | } 21 | ], 22 | "settings": { 23 | "c-cpp-flylint.cppcheck.standard": ["c99","c++14"], 24 | "files.associations": { 25 | "*.config": "yaml", 26 | "memory": "cpp", 27 | "utility": "cpp", 28 | "deque": "cpp", 29 | "vector": "cpp", 30 | "array": "cpp", 31 | "*.tcc": "cpp", 32 | "cctype": "cpp", 33 | "clocale": "cpp", 34 | "cstdint": "cpp", 35 | "cstdio": "cpp", 36 | "cstdlib": "cpp", 37 | "cstring": "cpp", 38 | "cwchar": "cpp", 39 | "cwctype": "cpp", 40 | "exception": "cpp", 41 | "functional": "cpp", 42 | "initializer_list": "cpp", 43 | "iosfwd": "cpp", 44 | "istream": "cpp", 45 | "limits": "cpp", 46 | "new": "cpp", 47 | "ostream": "cpp", 48 | "stdexcept": "cpp", 49 | "streambuf": "cpp", 50 | "string_view": "cpp", 51 | "system_error": "cpp", 52 | "tuple": "cpp", 53 | "type_traits": "cpp", 54 | "typeinfo": "cpp", 55 | "algorithm": "cpp", 56 | "chrono": "cpp", 57 | "condition_variable": "cpp", 58 | "future": "cpp", 59 | "arm_math.h": "c", 60 | "iostream": "cpp", 61 | "cmath": "cpp", 62 | "csignal": "cpp", 63 | "cstdarg": "cpp", 64 | "cstddef": "cpp", 65 | "ctime": "cpp", 66 | "unordered_map": "cpp", 67 | "fstream": "cpp", 68 | "iomanip": "cpp", 69 | "optional": "cpp", 70 | "sstream": "cpp", 71 | "utils.h": "c", 72 | "atomic": "cpp", 73 | "hash_map": "cpp", 74 | "strstream": "cpp", 75 | "bit": "cpp", 76 | "bitset": "cpp", 77 | "cinttypes": "cpp", 78 | "codecvt": "cpp", 79 | "compare": "cpp", 80 | "complex": "cpp", 81 | "concepts": "cpp", 82 | "forward_list": "cpp", 83 | "list": "cpp", 84 | "map": "cpp", 85 | "set": "cpp", 86 | "unordered_set": "cpp", 87 | "iterator": "cpp", 88 | "memory_resource": "cpp", 89 | "numeric": "cpp", 90 | "random": "cpp", 91 | "ratio": "cpp", 92 | "string": "cpp", 93 | "hash_set": "cpp", 94 | "slist": "cpp", 95 | "mutex": "cpp", 96 | "ranges": "cpp", 97 | "shared_mutex": "cpp", 98 | "stop_token": "cpp", 99 | "thread": "cpp", 100 | "cfenv": "cpp", 101 | "typeindex": "cpp", 102 | "valarray": "cpp", 103 | "variant": "cpp", 104 | "types": "cpp", 105 | "config": "cpp", 106 | "containers": "cpp", 107 | "readerwriter": "cpp", 108 | "charconv": "cpp", 109 | "image": "cpp", 110 | "imageutils": "cpp" 111 | } 112 | } 113 | } 114 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | ## Important Note 2 | 3 | The firmware in this repository is compatible with the ODrive v3.x (NRND) and is no longer under active development. 4 | 5 | Firmware for the new generation of ODrives ([ODrive Pro](https://odriverobotics.com/shop/odrive-pro), [S1](https://odriverobotics.com/shop/odrive-s1), [Micro](https://odriverobotics.com/shop/odrive-micro), etc.) is currently being actively maintained and developed, however its source code is currently not publicly available. Access may be available under NDA, please [reach out to us](mailto:info@odriverobotics.com) for inquiries. 6 | 7 | ## Overview 8 | 9 | ![ODrive Logo](https://static1.squarespace.com/static/58aff26de4fcb53b5efd2f02/t/59bf2a7959cc6872bd68be7e/1505700483663/Odrive+logo+plus+text+black.png?format=1000w) 10 | 11 | This project is all about accurately driving brushless motors, for cheap. The aim is to make it possible to use inexpensive brushless motors in high performance robotics projects, like [this](https://www.youtube.com/watch?v=WT4E5nb3KtY). 12 | 13 | | Branch | Build Status | 14 | |--------|--------------| 15 | | master | [![Build Status](https://travis-ci.org/madcowswe/ODrive.png?branch=master)](https://travis-ci.org/madcowswe/ODrive) | 16 | | devel | [![Build Status](https://travis-ci.org/madcowswe/ODrive.png?branch=devel)](https://travis-ci.org/madcowswe/ODrive) | 17 | 18 | [![pip install odrive (nightly)](https://github.com/madcowswe/ODrive/workflows/pip%20install%20odrive%20(nightly)/badge.svg)](https://github.com/madcowswe/ODrive/actions?query=workflow%3A%22pip+install+odrive+%28nightly%29%22) 19 | 20 | Please refer to the [Developer Guide](https://docs.odriverobotics.com/v/latest/developer-guide.html#) to get started with ODrive firmware development. 21 | 22 | 23 | ### Repository Structure 24 | * **Firmware**: ODrive firmware 25 | * **tools**: Python library & tools 26 | * **docs**: Documentation 27 | 28 | ### Other Resources 29 | 30 | * [Main Website](https://www.odriverobotics.com/) 31 | * [User Guide](https://docs.odriverobotics.com/) 32 | * [Forum](https://discourse.odriverobotics.com/) 33 | * [Chat](https://discourse.odriverobotics.com/t/come-chat-with-us/281) 34 | -------------------------------------------------------------------------------- /analysis/Simulation/TranslationalMass.py: -------------------------------------------------------------------------------- 1 | import os 2 | import matplotlib.pyplot as plt 3 | from control.matlab import * 4 | import numpy as np 5 | 6 | 7 | # Input: Current (A) 8 | # Output: Torque (Nm) 9 | # Params: Kt (Nm/A) 10 | def motor(Kt): 11 | return tf(Kt, 1) 12 | 13 | # Mass-Spring-Damper 14 | # Input: Force 15 | # Output: Position 16 | # Params: m (kg) 17 | # b 18 | # k (N/m) 19 | def mass(m, b, k): 20 | A = [[0, 1.], [-k/m, -b/m]] 21 | B = [[0], [1/m]] 22 | C = [[1., 0]] 23 | return ss(A, B, C, 0) 24 | 25 | # Input: Torque (Nm) 26 | # Output: Force (N) 27 | # Params: r (m) 28 | def pulley(r): 29 | return tf(r, 1) 30 | 31 | # Make s a transfer function s/1 32 | s = tf('s') 33 | print(s) 34 | 35 | # build a new transfer function using our variable s as a handy placeholder 36 | sys = 1 / (s*s + s + 1) 37 | print(sys) 38 | 39 | # Hit the system with a step command 40 | yout, T = step(sys) 41 | plt.plot(T, yout) 42 | 43 | # convert our continuous time model to discrete time via Tustin at 0.01s timestep 44 | sysd = c2d(tf(sys), 0.01, method='tustin') 45 | print(sysd) 46 | 47 | # Hit the discrete system with a step command, and sample it at 0.01 timestep from 0 to 14 seconds 48 | yout, T = step(sysd, np.arange(0, 14, 0.01)) 49 | plt.plot(T, yout) 50 | plt.legend(['Continuous', 'Discrete']) 51 | 52 | # Build a system based on the series connection of the motor, pulley, and mass "blocks" 53 | sys = series(motor(2.5), pulley(0.015), mass(0.10, .1, .1)) 54 | print(tf(sys)) 55 | 56 | # Step our series system, returning y (outputs) and x (states) 57 | yout, T, xout = step(sys, return_x=True) 58 | plt.figure() 59 | plt.plot(T, yout) 60 | plt.plot(T, xout) 61 | plt.legend(['Displacement', r'$x$', r'$\dot{x}$']) 62 | plt.show() -------------------------------------------------------------------------------- /analysis/cogging_torque/cogging_harmonics.py: -------------------------------------------------------------------------------- 1 | 2 | import numpy as np 3 | import matplotlib.pyplot as plt 4 | 5 | encoder_cpr = 2400 6 | stator_slots = 12 7 | pole_pairs = 7 8 | 9 | N = data.size 10 | fft = np.fft.rfft(data) 11 | freq = np.fft.rfftfreq(N, d=1./encoder_cpr) 12 | 13 | harmonics = [0] 14 | harmonics += [(i+1)*stator_slots for i in range(pole_pairs)] 15 | harmonics += [pole_pairs] 16 | harmonics += [(i+1)*2*pole_pairs for i in range(int(stator_slots/4))] 17 | 18 | 19 | fft_sparse = fft.copy() 20 | indicies = np.arange(fft_sparse.size) 21 | mask = [i not in harmonics for i in indicies] 22 | fft_sparse[mask] = 0.0 23 | interp_data = np.fft.irfft(fft_sparse) 24 | 25 | #%% 26 | 27 | #plt.figure() 28 | plt.subplot(3, 1, 1) 29 | plt.plot(data, label='raw') 30 | plt.plot(interp_data, label='selected harmonics IFFT') 31 | plt.title('cogging map') 32 | plt.xlabel('counts') 33 | plt.ylabel('A') 34 | plt.legend(loc='best') 35 | 36 | #plt.figure() 37 | plt.subplot(3, 1, 2) 38 | plt.stem(freq, np.abs(fft)/N, label='raw') 39 | plt.stem(freq[harmonics], np.abs(fft_sparse[harmonics])/N, markerfmt='ro', label='selected harmonics') 40 | plt.title('cogging map spectrum') 41 | plt.xlabel('cycles/turn') 42 | plt.ylabel('A') 43 | plt.legend(loc='best') 44 | 45 | #plt.figure() 46 | plt.subplot(3, 1, 3) 47 | plt.stem(freq, np.abs(fft)/N, label='raw') 48 | plt.stem(freq[harmonics], np.abs(fft_sparse[harmonics])/N, markerfmt='ro', label='selected harmonics') 49 | plt.title('cogging map spectrum') 50 | plt.xlabel('cycles/turn') 51 | plt.ylabel('A') 52 | plt.legend(loc='best') -------------------------------------------------------------------------------- /analysis/filterpoles.py: -------------------------------------------------------------------------------- 1 | 2 | import numpy as np 3 | import sympy as sp 4 | from scipy.integrate import solve_ivp 5 | import matplotlib.pyplot as plt 6 | 7 | do_mass_spring = True 8 | do_PLL = False 9 | 10 | bandwidth = 10 11 | 12 | pos_ref = 0 13 | vel_ref = 0 14 | init_pos = 1000 15 | init_vel = 0 16 | 17 | plotend = 1 18 | plotfrequency = 1000.0 19 | 20 | fig, ax1 = plt.subplots() 21 | 22 | if do_mass_spring: 23 | # 2nd order system response with manipulation of velocity only 24 | # This is similar to a mass/spring/damper system 25 | # pos_dot = vel 26 | # vel_dot = Kp * delta_pos + Ki * delta_vel 27 | 28 | Ki = 2.0 * bandwidth 29 | Kp = 0.25 * Ki**2 30 | 31 | def get_Xdot(t, X): 32 | pos = X[0] 33 | vel = X[1] 34 | 35 | pos_err = pos_ref - pos 36 | vel_err = vel_ref - vel 37 | 38 | pos_dot = vel 39 | vel_dot = Kp * pos_err + Ki * vel_err 40 | 41 | Xdot = [pos_dot, vel_dot] 42 | return Xdot 43 | 44 | sol = solve_ivp(get_Xdot, (0.0, plotend), [init_pos, init_vel], t_eval=np.linspace(0, plotend, plotend*plotfrequency)) 45 | 46 | color = 'tab:red' 47 | ax1.set_xlabel('time (s)') 48 | ax1.set_ylabel('pos', color=color) 49 | ax1.plot(np.transpose(sol.t), np.transpose(sol.y[0,:]), label='physical mass', color=color) 50 | ax1.tick_params(axis='y', labelcolor=color) 51 | 52 | ax2 = ax1.twinx() # instantiate a second axes that shares the same x-axis 53 | 54 | color = 'tab:blue' 55 | ax2.set_ylabel('vel', color=color) # we already handled the x-label with ax1 56 | ax2.plot(np.transpose(sol.t), np.transpose(sol.y[1,:]), label='physical mass', color=color) 57 | ax2.tick_params(axis='y', labelcolor=color) 58 | 59 | 60 | if do_PLL: 61 | # 2nd order system response with a "slipping displacement" term directly on position 62 | # This formulation is given in the sensorless PLL paper 63 | # pos_dot = vel + Kp * delta_pos 64 | # vel_dot = Ki * delta_pos 65 | 66 | Kp = 2.0 * bandwidth 67 | Ki = 0.25 * Kp**2 68 | 69 | def get_Xdot(t, X): 70 | pos = X[0] 71 | vel = X[1] 72 | 73 | pos_err = pos_ref - pos 74 | vel_err = vel_ref - vel 75 | 76 | pos_dot = vel + Kp * pos_err 77 | vel_dot = Ki * pos_err 78 | 79 | Xdot = [pos_dot, vel_dot] 80 | return Xdot 81 | 82 | sol = solve_ivp(get_Xdot, (0.0, plotend), [init_pos, init_vel], t_eval=np.linspace(0, plotend, plotend*plotfrequency)) 83 | 84 | plt.plot(np.transpose(sol.t), np.transpose(sol.y[0,:]), label='PLL pos') 85 | plt.plot(np.transpose(sol.t), np.transpose(sol.y[1,:]), label='PLL vel') 86 | 87 | 88 | 89 | plt.legend() 90 | plt.show(block=True) -------------------------------------------------------------------------------- /analysis/motor_analysis/350kvTP.PNG: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/analysis/motor_analysis/350kvTP.PNG -------------------------------------------------------------------------------- /analysis/motor_analysis/350kvVelli.PNG: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/analysis/motor_analysis/350kvVelli.PNG -------------------------------------------------------------------------------- /analysis/motor_analysis/VelliPlot.m: -------------------------------------------------------------------------------- 1 | % limits 2 | Imax = 64; %A 3 | Umax = 22; %V 4 | Irange = 100; %A. Range for plotting current 5 | omegaMax = 2000; %rad/s mechanical. For plotting voltage ellipses 6 | omegastep = 200; %rad/s mechanical. For plotting voltage ellipses 7 | 8 | 9 | %% 10 | %350 kv motor 11 | lambda = 2.24/1000; 12 | L = 23e-6; 13 | R = 32e-3; 14 | pp = 7; Poles = pp*2; 15 | Ld = L; 16 | Lq = L; 17 | 18 | % %% 19 | % % Donkey 20 | % kv = 820; 21 | % lambda = 60/(kv*2*pi*pp*sqrt(3)); 22 | % L = 8e-6; %Guess! TODO: measure 23 | % R = 30e-3; %Guess! TODO: measure 24 | % pp = 7; Poles = pp*2; 25 | % Ld = L; 26 | % Lq = L; 27 | 28 | %% 29 | Istep = Irange/400; 30 | Idplt = repmat(-Irange:Istep:Irange,801,1); 31 | Iqplt = repmat((-Irange:Istep:Irange)',1,801); 32 | UmaxSq = (Umax/sqrt(3))^2; 33 | 34 | t = linspace(0,2*pi); 35 | IdMaxt = Imax*cos(t); 36 | IqMaxt = Imax*sin(t); 37 | 38 | %% 39 | figure(1) 40 | plot(IdMaxt, IqMaxt); 41 | 42 | hold on; 43 | 44 | %Plot torque 45 | %[c,h] = contour(Idplt,Iqplt, (Poles/2).*(3/2).*(lambda.*Iqplt + (Ld-Lq).*Iqplt.*Idplt), -5:0.25:5); 46 | %clabel(c,h,'LabelSpacing',500); 47 | 48 | %Plot voltage ellipses 49 | EllRHS = Ld^2.*(lambda/Ld + Idplt).^2 + Lq^2.*Iqplt.^2; 50 | omegaAtEllipse = sqrt(UmaxSq./EllRHS); 51 | [c,h] = contour(Idplt,Iqplt, omegaAtEllipse./(Poles/2), 0:omegastep:omegaMax); 52 | clabel(c,h,'LabelSpacing',500); 53 | xlabel 'Id (A)' 54 | ylabel 'Iq (A)' 55 | colormap(jet) 56 | c = colorbar; 57 | %c.Label.String = 'Speed (rad/s)'; 58 | ylabel(c,'Speed (mechanical rad/s)') 59 | grid on 60 | axis equal 61 | 62 | %plot infinite speed point 63 | plot(-lambda/Ld, 0, 'r*'); 64 | 65 | hold off; 66 | 67 | %% 68 | figure(2) 69 | 70 | %fw range 71 | t = linspace(pi/2,pi); 72 | IdMaxt = Imax*cos(t); 73 | IqMaxt = Imax*sin(t); 74 | Tmaxt = (Poles/2).*(3/2).*(lambda.*IqMaxt + (Ld-Lq).*IqMaxt.*IdMaxt); 75 | EllRHSmaxt = Ld^2.*(lambda/Ld + IdMaxt).^2 + Lq^2.*IqMaxt.^2; 76 | omegamaxt = sqrt(UmaxSq./EllRHSmaxt); 77 | 78 | %MTPA range 79 | MTPAmaxtId = 0; %TODO make work for salient machines 80 | MTPAmaxtIq = Imax; 81 | TmaxtMTPA = (Poles/2).*(3/2).*(lambda.*MTPAmaxtIq + (Ld-Lq).*MTPAmaxtIq.*MTPAmaxtId); 82 | Tmaxt = [repmat(TmaxtMTPA, 1, 100) Tmaxt]; 83 | omegamaxt = [linspace(0,omegamaxt(1)) omegamaxt]; 84 | 85 | %Present mechanical speed 86 | omegamaxt = omegamaxt./(Poles/2); 87 | 88 | Pmaxt = Tmaxt.*omegamaxt; 89 | 90 | %plotyy(t, Tmaxt, t, omegamaxt); 91 | %plotyy(t, Tmaxt, t, Pmaxt); 92 | %plotyy(t, Pmaxt, t, omegamaxt); 93 | 94 | h = plotyy(omegamaxt, Tmaxt, omegamaxt, Pmaxt); 95 | grid on 96 | xlabel 'Speed (mechanical rad/s)' 97 | ylabel 'Torque (Nm)' 98 | ylabel(h(2), 'Power (W)'); -------------------------------------------------------------------------------- /analysis/numeric_path_opt/Main.m: -------------------------------------------------------------------------------- 1 | %Params 2 | AccelPerA = 3000; 3 | phaseR = 0.033; 4 | Ts = 0.001; 5 | N = 50; 6 | thetaFinal = 200; 7 | x0 = [0;0]; 8 | 9 | %system definition 10 | %X = [theta; omega] 11 | Ac = [0 1; 12 | 0 0]; 13 | Bc = [0; 14 | AccelPerA]; 15 | C = 0; 16 | D = 0; 17 | 18 | SYSC = ss(Ac, Bc, [], []); 19 | SYSD = c2d(SYSC, Ts, 'zoh'); 20 | [Phi, Gamma] = predictionmatrices(SYSD.a, SYSD.b, SYSD.c, N); 21 | 22 | Df = Gamma(end-1:end,:); 23 | ff = [thetaFinal; 0]; 24 | 25 | H = 2*eye(N)*(3/2)*phaseR*Ts; 26 | [u, fval] = quadprog(H,[],[],[],Df,ff); 27 | 28 | xv = reshape(Gamma*u, 2,N)'; 29 | x = xv(:,1); 30 | v = xv(:,2); 31 | 32 | kv350_lambda = 2.2e-3; 33 | power = u.*v.*(3/2)*kv350_lambda; 34 | 35 | Vbus = 24; 36 | Ib = power/Vbus; 37 | Im = u; 38 | duty = Ib./Im; 39 | CapIsqr = (duty.*(Ib-Im)).^2 + ((1-duty).*Ib).^2; 40 | CapIrms = sqrt(sum(CapIsqr)/N); 41 | CapR = 0.08; 42 | Ncaps = 8; 43 | Cappow = (CapIrms/Ncaps)^2 * CapR 44 | -------------------------------------------------------------------------------- /analysis/numeric_path_opt/predictionmatrices.m: -------------------------------------------------------------------------------- 1 | function [Phi, Gamma, Lambda] = predictionmatrices(A, B, C, N) 2 | %UNTITLED2 Summary of this function goes here 3 | % Detailed explanation goes here 4 | 5 | n = size(A,1); 6 | Atilde = [A; zeros((N-1)*n, n)]; 7 | k = [zeros(n, N*n); -kron(eye(N-1), A) zeros((N-1)*n,n)] + eye(N*n); 8 | 9 | Phi = k\Atilde; 10 | Gamma = k\kron(eye(N), B); 11 | Lambda = kron(eye(N), C); 12 | 13 | end 14 | 15 | -------------------------------------------------------------------------------- /analysis/thermistors.py: -------------------------------------------------------------------------------- 1 | #%% 2 | from odrive.utils import calculate_thermistor_coeffs 3 | 4 | Rload = 3300 # 2000 for ODrive v4 5 | R_25 = 10000 6 | Beta = 3434 7 | Tmin = 0 8 | Tmax = 140 9 | calculate_thermistor_coeffs(3, Rload, R_25, Beta, Tmin, Tmax, True) 10 | -------------------------------------------------------------------------------- /dockerbuild.sh: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env bash 2 | function cleanup { 3 | echo "Removing previous build artifacts" 4 | rm -rf build/ Firmware/autogen Firmware/build Firmware/.tup 5 | docker rm odrive-build-cont 6 | } 7 | 8 | function gc { 9 | cleanup 10 | docker rmi odrive-build-img 11 | docker image prune 12 | } 13 | 14 | function build { 15 | cleanup 16 | 17 | echo "Building the build-environment image" 18 | docker build -t odrive-build-img . 19 | 20 | echo "Build in container" 21 | docker run -it -v $(pwd):/ODrive --name odrive-build-cont --user $(id -u) odrive-build-img:latest 22 | } 23 | 24 | function usage { 25 | echo "usage: $0 (build | cleanup | gc)" 26 | echo 27 | echo "build -- build in docker and extract the artifacts." 28 | echo "cleanup -- remove build artifacts from previous build" 29 | echo "gc -- remove all build images and containers" 30 | } 31 | 32 | case $1 in 33 | build) 34 | build 35 | ;; 36 | cleanup) 37 | cleanup 38 | ;; 39 | gc) 40 | gc 41 | ;; 42 | *) 43 | usage 44 | ;; 45 | esac 46 | -------------------------------------------------------------------------------- /docs/Makefile: -------------------------------------------------------------------------------- 1 | # Minimal makefile for Sphinx documentation 2 | # 3 | 4 | # You can set these variables from the command line, and also 5 | # from the environment for the first two. 6 | SPHINXOPTS ?= 7 | SPHINXBUILD ?= sphinx-build 8 | SOURCEDIR = . 9 | BUILDDIR = _build 10 | 11 | # Put it first so that "make" without argument is like "make help". 12 | help: 13 | @$(SPHINXBUILD) -M help "$(SOURCEDIR)" "$(BUILDDIR)" $(SPHINXOPTS) $(O) 14 | 15 | .PHONY: help Makefile 16 | 17 | # Catch-all target: route all unknown targets to Sphinx using the new 18 | # "make mode" option. $(O) is meant as a shortcut for $(SPHINXOPTS). 19 | %: Makefile 20 | @$(SPHINXBUILD) -M $@ "$(SOURCEDIR)" "$(BUILDDIR)" $(SPHINXOPTS) $(O) 21 | -------------------------------------------------------------------------------- /docs/analog-input.rst: -------------------------------------------------------------------------------- 1 | ================================================================================ 2 | Analog Input 3 | ================================================================================ 4 | 5 | Analog inputs can be used to measure voltages between 0 and 3.3V. 6 | ODrive uses a 12 bit ADC (4096 steps) and so has a maximum resolution of 0.8 mV. 7 | A GPIO must be configured with :code:`.config.gpioX_mode = GPIO_MODE_ANALOG_IN` before it can be used as an analog input. 8 | To read the voltage on GPIO1 in odrivetool the following would be entered: :code:`odrv0.get_adc_voltage(1)`. 9 | 10 | Similar to RC PWM input, analog inputs can also be used to feed any of the numerical properties that are visible in :code:`odrivetool`. 11 | This is done by configuring :code:`odrv0.config.gpio3_analog_mapping` and :code:`odrv0.config.gpio4_analog_mapping`. 12 | Refer to :ref:`RC PWM ` for instructions on how to configure the mappings. 13 | 14 | You may also retrieve voltage measurements from analog inputs via the CAN protocol by sending the Get ADC Voltage message with the GPIO number of the analog input you wish to read. Refer to :ref: `CAN Protocol ` for guidance on how to use the CAN Protocol. -------------------------------------------------------------------------------- /docs/changelog.rst: -------------------------------------------------------------------------------- 1 | .. _changelog: 2 | 3 | ================================================================================ 4 | CHANGELOG 5 | ================================================================================ 6 | 7 | 8 | .. include:: ../CHANGELOG.md 9 | :parser: myst_parser.sphinx_ -------------------------------------------------------------------------------- /docs/configuring-eclipse.rst: -------------------------------------------------------------------------------- 1 | .. _configuring-eclipse: 2 | 3 | ================================================================================ 4 | Setting up Eclipse development environment 5 | ================================================================================ 6 | 7 | .. contents:: 8 | :depth: 1 9 | :local: 10 | 11 | Install 12 | ------------------------------------------------------------------------------- 13 | 14 | * Install `Eclipse IDE for C/C++ Developers. `_ 15 | * Install the `OpenOCD Eclipse plugin. `_ 16 | 17 | Import Project 18 | ------------------------------------------------------------------------------- 19 | 20 | * **File** -> **Import** -> **C/C++** -> Existing Code as Makefile Project 21 | * Browse for existing code location, find the OdriveFirmware root. 22 | * In the Toolchain options, select `Cross GCC` 23 | * Hit **Finish** 24 | * Build the project (press :kbd:`ctrl-B`) 25 | 26 | .. figure:: figures/CodeAsMakefile.png 27 | :scale: 50 % 28 | :alt: Toolchain options 29 | 30 | Load the Launch Configuration 31 | ------------------------------------------------------------------------------- 32 | 33 | * **File** -> **Import** -> **Run/Debug** -> **Launch Configurations** -> **Next** 34 | * Highlight (don't tick) the OdriveFirmare folder in the left column 35 | * Tick OdriveFirmware.launch in the right column 36 | * Hit **Finish** 37 | 38 | .. figure:: figures/ImportLaunch.png 39 | :scale: 50 % 40 | :alt: Launch Configurations 41 | 42 | Launch! 43 | ------------------------------------------------------------------------------- 44 | 45 | * Make sure the programmer is connected to the board as per :ref:`Flashing the firmware `. 46 | * Press the down-arrow of the debug symbol in the toolbar, and hit Debug Configurations 47 | * You can also hit **Run** -> **Debug Configurations** 48 | 49 | * Highlight the debug configuration you imported, called OdriveFirmware. 50 | If you do not see the imported launch configuration rename your project to `ODriveFirmware` or edit the launch configuration to match your project name by unfiltering unavailable projects: 51 | 52 | .. figure:: figures/LaunchConfigFilter.png 53 | :scale: 50 % 54 | :alt: Launch Configurations Filters 55 | 56 | * Hit **Debug** 57 | * Eclipse should flash the board for you and the program should start halted on the first instruction in `Main` 58 | * Set beakpoints, step, hit Resume, etc. 59 | * Make some cool features! ;D -------------------------------------------------------------------------------- /docs/fibre_types/com_odriverobotics_ODrive.rst: -------------------------------------------------------------------------------- 1 | ODrive Reference 2 | ================ 3 | 4 | .. fibreclass:: com.odriverobotics.ODrive 5 | 6 | 7 | .. fibrenamespace:: com.odriverobotics.ODrive 8 | :bitfields: 9 | :enums: 10 | :classes: 11 | :namespaces: 12 | -------------------------------------------------------------------------------- /docs/figures/CAN_Bus_Drawing.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/docs/figures/CAN_Bus_Drawing.png -------------------------------------------------------------------------------- /docs/figures/CodeAsMakefile.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/docs/figures/CodeAsMakefile.png -------------------------------------------------------------------------------- /docs/figures/Endstop_configuration.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/docs/figures/Endstop_configuration.png -------------------------------------------------------------------------------- /docs/figures/ImportLaunch.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/docs/figures/ImportLaunch.png -------------------------------------------------------------------------------- /docs/figures/LaunchConfigFilter.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/docs/figures/LaunchConfigFilter.png -------------------------------------------------------------------------------- /docs/figures/Non_Isolated_CAN_Wiring.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/docs/figures/Non_Isolated_CAN_Wiring.png -------------------------------------------------------------------------------- /docs/figures/ODriveBasicWiring.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/docs/figures/ODriveBasicWiring.png -------------------------------------------------------------------------------- /docs/figures/TrapTrajPosVel.PNG: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/docs/figures/TrapTrajPosVel.PNG -------------------------------------------------------------------------------- /docs/figures/controller_with_ff.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/docs/figures/controller_with_ff.png -------------------------------------------------------------------------------- /docs/figures/endstop_figure.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/docs/figures/endstop_figure.png -------------------------------------------------------------------------------- /docs/figures/ground_loop_bad.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/docs/figures/ground_loop_bad.png -------------------------------------------------------------------------------- /docs/figures/ground_loop_fix.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/docs/figures/ground_loop_fix.png -------------------------------------------------------------------------------- /docs/figures/liveplotter-iq-omega.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/docs/figures/liveplotter-iq-omega.png -------------------------------------------------------------------------------- /docs/figures/liveplotter-pos-estimate.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/docs/figures/liveplotter-pos-estimate.png -------------------------------------------------------------------------------- /docs/figures/mech_dimensions.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/docs/figures/mech_dimensions.png -------------------------------------------------------------------------------- /docs/figures/pinout.csv: -------------------------------------------------------------------------------- 1 | #,Label,GPIO_MODE_DIGITAL,GPIO_MODE_ANALOG_IN,GPIO_MODE_UART_A,GPIO_MODE_UART_B,GPIO_MODE_PWM,GPIO_MODE_CAN_A,GPIO_MODE_I2C_A,GPIO_MODE_ENC0,GPIO_MODE_ENC1,GPIO_MODE_MECH_BRAKE 2 | 0,not a pin,,,,,,,,,, 3 | 1,GPIO1 (+),general purpose,analog input,**UART_A.TX**,,PWM0.0,,,,,mechanical brake 4 | 2,GPIO2 (+),general purpose,analog input,**UART_A.RX**,,PWM0.1,,,,,mechanical brake 5 | 3,GPIO3,general purpose,**analog input**,,**UART_B.TX**,PWM0.2,,,,,mechanical brake 6 | 4,GPIO4,general purpose,**analog input**,,**UART_B.RX**,PWM0.3,,,,,mechanical brake 7 | 5,GPIO5,general purpose,**analog input (*)**,,,,,,,,mechanical brake 8 | 6,GPIO6 (*) (+),**general purpose**,,,,,,,,,mechanical brake 9 | 7,GPIO7 (*) (+),**general purpose**,,,,,,,,,mechanical brake 10 | 8,GPIO8 (*) (+),**general purpose**,,,,,,,,,mechanical brake 11 | 9,M0.A,general purpose,,,,,,,**ENC0.A**,, 12 | 10,M0.B,general purpose,,,,,,,**ENC0.B**,, 13 | 11,M0.Z,**general purpose**,,,,,,,,, 14 | 12,M1.A,general purpose,,,,,,I2C.SCL,,**ENC1.A**, 15 | 13,M1.B,general purpose,,,,,,I2C.SDA,,**ENC1.B**, 16 | 14,M1.Z,**general purpose**,,,,,,,,, 17 | 15,not exposed,general purpose,,,,,**CAN_A.RX**,I2C.SCL,,, 18 | 16,not exposed,general purpose,,,,,**CAN_A.TX**,I2C.SDA,,, -------------------------------------------------------------------------------- /docs/figures/secondOrderResponse.PNG: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/docs/figures/secondOrderResponse.PNG -------------------------------------------------------------------------------- /docs/figures/stlink-wiring.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/docs/figures/stlink-wiring.jpg -------------------------------------------------------------------------------- /docs/figures/thermistor-voltage-divider.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/docs/figures/thermistor-voltage-divider.png -------------------------------------------------------------------------------- /docs/figures/torque_mode_vel_limit.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/odriverobotics/ODrive/f9b5419c820c6fb2f609322a5131cdf8c5f71657/docs/figures/torque_mode_vel_limit.png -------------------------------------------------------------------------------- /docs/index.rst: -------------------------------------------------------------------------------- 1 | .. ODrive Documentation documentation master file, created by 2 | sphinx-quickstart on Wed Nov 3 20:01:31 2021. 3 | You can adapt this file completely to your liking, but it should at least 4 | contain the root `toctree` directive. 5 | 6 | ================================================================================ 7 | ODrive Documentation 8 | ================================================================================ 9 | 10 | Welcome to the ODrive V3.6 documentation homepage! 11 | 12 | This project strives to bring high performance motor control to makers, all of the source code is 13 | open source and available on github `here. `__ 14 | 15 | .. note:: 16 | 17 | This documentation is specifically for V3.6, for ODrive Pro Beta click `here. `__ 18 | 19 | `ODrive Robotics homepage. `__ 20 | 21 | Table of Contents 22 | -------------------------------------------------------------------------------- 23 | 24 | .. toctree:: 25 | :maxdepth: 1 26 | :caption: General 27 | 28 | getting-started 29 | odrivetool 30 | control-modes 31 | commands 32 | encoders 33 | control 34 | troubleshooting 35 | specifications 36 | ground-loops 37 | 38 | .. toctree:: 39 | :maxdepth: 1 40 | :caption: Tutorials 41 | 42 | Hoverboard Guide 43 | migration 44 | CAN Guide 45 | Motor Guide 46 | Encoder Guide 47 | 48 | 49 | .. toctree:: 50 | :maxdepth: 1 51 | :caption: Interfaces and Protocols 52 | 53 | protocol 54 | Pinout 55 | usb 56 | uart 57 | native-protocol 58 | ascii-protocol 59 | can-protocol 60 | Step & Direction 61 | rc-pwm 62 | analog-input 63 | endstops 64 | thermistors 65 | 66 | 67 | .. fibreautosummary:: com.odriverobotics.ODrive 68 | :caption: ODrive Device API 69 | 70 | 71 | .. toctree:: 72 | :maxdepth: 1 73 | :caption: For ODrive Developers 74 | 75 | developer-guide 76 | configuring-vscode 77 | configuring-eclipse 78 | 79 | .. toctree:: 80 | :caption: CHANGELOG 81 | 82 | changelog.rst -------------------------------------------------------------------------------- /docs/make.bat: -------------------------------------------------------------------------------- 1 | @ECHO OFF 2 | 3 | pushd %~dp0 4 | 5 | REM Command file for Sphinx documentation 6 | 7 | if "%SPHINXBUILD%" == "" ( 8 | set SPHINXBUILD=sphinx-build 9 | ) 10 | set SOURCEDIR=. 11 | set BUILDDIR=_build 12 | 13 | if "%1" == "" goto help 14 | 15 | %SPHINXBUILD% >NUL 2>NUL 16 | if errorlevel 9009 ( 17 | echo. 18 | echo.The 'sphinx-build' command was not found. Make sure you have Sphinx 19 | echo.installed, then set the SPHINXBUILD environment variable to point 20 | echo.to the full path of the 'sphinx-build' executable. Alternatively you 21 | echo.may add the Sphinx directory to PATH. 22 | echo. 23 | echo.If you don't have Sphinx installed, grab it from 24 | echo.http://sphinx-doc.org/ 25 | exit /b 1 26 | ) 27 | 28 | %SPHINXBUILD% -M %1 %SOURCEDIR% %BUILDDIR% %SPHINXOPTS% %O% 29 | goto end 30 | 31 | :help 32 | %SPHINXBUILD% -M help %SOURCEDIR% %BUILDDIR% %SPHINXOPTS% %O% 33 | 34 | :end 35 | popd 36 | -------------------------------------------------------------------------------- /docs/native-protocol.rst: -------------------------------------------------------------------------------- 1 | .. _native-protocol: 2 | 3 | ================================================================================ 4 | Native Protocol 5 | ================================================================================ 6 | 7 | This protocol is what the :code:`odrivetool` uses to talk to the ODrive. 8 | If you have a choice, this is the recommended protocol for all applications. 9 | The native protocol runs on :ref:`USB ` and on :ref:`UART `. 10 | 11 | Python 12 | -------------------------------------------------------------------------------- 13 | 14 | The :code:`odrivetool` you installed as part of the :ref:`Getting Started guide ` comes with a library that you can use to easily control the ODrive from Python. 15 | 16 | Assuming you already installed the odrive library (:code:`pip install odrive`), the simplest program to control the ODrive is this: 17 | 18 | .. code:: Python 19 | 20 | import odrive 21 | odrv0 = odrive.find_any() 22 | print(str(odrv0.vbus_voltage)) 23 | 24 | 25 | For a more comprehensive example, see `tools/odrive_demo.py `_. 26 | 27 | Other Languages 28 | -------------------------------------------------------------------------------- 29 | 30 | We don't have an official library for you just yet. Check the community, there might be someone working on it. 31 | If you want to write a library yourself, refer to the :ref:`native protocol specification `. 32 | You are of course welcome to contribute it back. -------------------------------------------------------------------------------- /docs/pinout.rst: -------------------------------------------------------------------------------- 1 | .. _pinout-chart: 2 | 3 | ================================================================================ 4 | ODrive v3.x Pinout 5 | ================================================================================ 6 | 7 | .. contents:: 8 | :depth: 1 9 | :local: 10 | 11 | .. ODrive v4.1 12 | .. -------------------------------------------------------------------------------- 13 | 14 | .. **TODO** 15 | 16 | .. ODrive v3.x 17 | .. -------------------------------------------------------------------------------- 18 | 19 | .. csv-table:: Pinout Table 20 | :file: figures/pinout.csv 21 | :header-rows: 1 22 | 23 | **key:** 24 | 25 | * **(*)** ODrive v3.5 and later. 26 | 27 | * **(+)** On ODrive v3.5 and later these pins have noise suppression filters. This is useful for step/dir input. 28 | 29 | Notes 30 | -------------------------------------------------------------------------------- 31 | 32 | * Changes to the pin configuration only take effect after :code:`odrv0.save_configuration()` and :code:`odrv0.reboot()` 33 | * **Bold font** marks the default configuration. 34 | * If a GPIO is set to an unsupported mode it will be left uninitialized. 35 | * When setting a GPIO to a special purpose mode (e.g. :code:`GPIO_MODE_UART_A`) you must also enable the corresponding feature (e.g. :code:`.config.enable_uart_a`). 36 | * Digital mode is a general purpose mode that can be used for these functions: step, dir, enable, encoder index, hall effect encoder, SPI encoder nCS. 37 | * You must also connect GND between ODrive and your other board. 38 | * ODrive v3.3 and onward have 5V tolerant GPIO pins. 39 | * Simultaneous operation of UART_A and UART_B is currently not supported. 40 | -------------------------------------------------------------------------------- /docs/rc-pwm.rst: -------------------------------------------------------------------------------- 1 | .. _rc-pwm-doc: 2 | 3 | ================================================================================ 4 | RC PWM input 5 | ================================================================================ 6 | 7 | .. contents:: 8 | :depth: 1 9 | :local: 10 | 11 | You can control the ODrive directly from a hobby RC receiver. 12 | 13 | Any of the numerical parameters that are writable from the ODrive Tool can be hooked up to a PWM input. 14 | The :ref:`Pinout ` tells you which pins are PWM input capable. As an example, we'll configure GPIO4 to control the angle of axis 0. 15 | We want the axis to move within a range of -2 to 2 turns. 16 | 17 | #. Make sure you're able control the axis 0 angle by writing to :code:`odrv0.axis0.controller.input_pos`. 18 | If you need help with this follow the :ref:`getting started guide `. 19 | #. If you want to control your ODrive with the PWM input without using anything else to activate the ODrive, you can configure the ODrive such that axis 0 automatically goes operational at startup. 20 | See :ref:`here ` for more information. 21 | #. In ODrive Tool, configure the PWM input mapping 22 | 23 | .. code:: iPython 24 | 25 | odrv0.config.gpio4_mode = GPIO_MODE_PWM 26 | odrv0.config.gpio4_pwm_mapping.min = -2 27 | odrv0.config.gpio4_pwm_mapping.max = 2 28 | odrv0.config.gpio4_pwm_mapping.endpoint = odrv0.axis0.controller._input_pos_property 29 | 30 | .. note:: 31 | 32 | you can disable the input by setting :code:`odrv0.config.gpio4_pwm_mapping.endpoint = None` 33 | 34 | #. Save the configuration and reboot 35 | 36 | .. code:: iPython 37 | 38 | odrv0.save_configuration() 39 | odrv0.reboot() 40 | 41 | #. With the ODrive powered off, connect the RC receiver ground to the ODrive's GND and one of the RC receiver signals to GPIO4. 42 | You may try to power the receiver from the ODrive's 5V supply if it doesn't draw too much power. Power up the the RC transmitter. 43 | You should now be able to control axis 0 from one of the RC sticks. 44 | 45 | Be sure to setup the Failsafe feature on your RC Receiver so that if connection is lost between the remote and the receiver, the receiver outputs 0 for the velocity setpoint of both axes (or whatever is safest for your configuration). 46 | Also note that if the receiver turns off (loss of power, etc) or if the signal from the receiver to the ODrive is lost (wire comes unplugged, etc), the ODrive will continue the last commanded velocity setpoint. 47 | There is currently no timeout function in the ODrive for PWM inputs. -------------------------------------------------------------------------------- /docs/specifications.rst: -------------------------------------------------------------------------------- 1 | ================================================================================ 2 | Specifications 3 | ================================================================================ 4 | 5 | .. contents:: 6 | :depth: 1 7 | :local: 8 | 9 | Electrical Specifications 10 | -------------------------------------------------------------------------------- 11 | 12 | Besides the input voltage range, (12V to 24V for ODrive v3.6 24V, 12V to 56V for ODrive v3.6 56V), the electrical specifications of both version of ODrive v3.6 are the same. 13 | 14 | .. note:: ODrive versions after v3.5 are closed-source with respect to board files and schematics. 15 | 16 | ODrive v3.6 24V and 56V 17 | ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ 18 | 19 | * Peak current per motor: 120 Amps 20 | * Max continuous current depends on cooling. See `this `__ for more details. 21 | * Heatsink in still air: 40A per channel 22 | * Heatsink with basic fan cooling: 75A per channel 23 | * Heatsink with overkill fan cooling: 90A per channel 24 | * Max motor RPM: This depends on your power supply voltage, motor, and encoder. It is the lesser of: 25 | * motor RPM limit 26 | * encoder RPM limit 27 | * motor KV * 0.7 * Supply voltage 28 | * 35000 eRPM / # of motor pole pairs 29 | * (840M counts/minute) / encoder counts per revolution (for incremental encoders - 4 x pulses per revolution). 30 | 31 | Schematic 32 | ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ 33 | 34 | The electrical schematic for ODrive v3.5 is available `here `__ in PDF format. 35 | 36 | Mechanical Specifications 37 | -------------------------------------------------------------------------------- 38 | 39 | STEP File 40 | ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ 41 | 42 | A step file for ODrive v3.5 is available `here `__. 43 | 44 | Board Outline and Mounting Hole Dimensions 45 | ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ 46 | 47 | .. image:: figures/mech_dimensions.png 48 | :scale: 30 % 49 | :align: center 50 | :alt: board dimensions 51 | -------------------------------------------------------------------------------- /docs/uart.rst: -------------------------------------------------------------------------------- 1 | .. _uart-doc: 2 | 3 | ================================================================================ 4 | UART Interface 5 | ================================================================================ 6 | 7 | The ODrive's :code:`UART_A` interface is enabled by default with a baudrate of 115200 on the pins as shown in :ref:`Pinout `. 8 | 9 | To use UART connect it like this: 10 | 11 | * Tx of the ODrive <=> Rx of other device 12 | * Rx of the ODrive <=> Tx of other device 13 | * GND of the ODrive (use any GND pin on J3 of the ODrive) <=> GND of the other device 14 | 15 | The logic level of the ODrive is 3.3V. The GPIOs are 5V tolerant. 16 | 17 | You can use :code:`odrv0.config.uart_a_baudrate` to change the baudrate and :code:`odrv0.config.enable_uart_a` to disable/reenable :code:`UART_A`. 18 | The :code:`UART_A` port can run the :ref:`Native Protocol ` or the :ref:`ASCII Protocol `, but not both at the same time. 19 | You can configure this by setting :code:`odrv0.config.uart0_protocol` to either :code:`STREAM_PROTOCOL_TYPE_ASCII_AND_STDOUT` for the ASCII protocol or :code:`STREAM_PROTOCOL_TYPE_FIBRE` for the native protocol. 20 | 21 | How to use UART on GPIO3/4 22 | -------------------------------------------------------------------------------- 23 | 24 | If you need GPIO1/2 for some function other than UART you can disable :code:`UART_A` and instead use :code:`UART_B` on GPIO3/4. Here's how you do it: 25 | 26 | .. code:: iPython 27 | 28 | odrv0.config.enable_uart_a = False 29 | odrv0.config.gpio1_mode = GPIO_MODE_DIGITAL 30 | odrv0.config.gpio2_mode = GPIO_MODE_DIGITAL 31 | odrv0.config.enable_uart_b = True 32 | odrv0.config.gpio3_mode = GPIO_MODE_UART_B 33 | odrv0.config.gpio4_mode = GPIO_MODE_UART_B 34 | odrv0.reboot() 35 | -------------------------------------------------------------------------------- /docs/usb.rst: -------------------------------------------------------------------------------- 1 | .. _usb-doc: 2 | 3 | ================================================================================ 4 | USB 5 | ================================================================================ 6 | 7 | This page documents the low level USB configuration. 8 | If you're looking for a higher level protocol documentation see :ref:`Native Protocol ` and :ref:`ASCII Protocol `. 9 | 10 | This page assumes that you are familiar with the general USB architecture, in particular with terms like "configuration", "interface" and "endpoint". 11 | 12 | On USB the ODrive provides a single configuration which is a composite device consisting of a CDC device (virtual COM port) and a vendor specific device. 13 | 14 | .. dropdown:: What is a composite device? 15 | 16 | A composite device is a device where interfaces are grouped by interface association descriptors. 17 | For such devices, the host OS loads an intermediate driver, so that each of the interface groups can be treated like a separate device and have its own host-side driver attached. 18 | 19 | 20 | The following interface groups are present: 21 | 22 | * Interface Association: Communication Device Class (CDC) 23 | * Interface 0: 24 | * Endpoint `0x82`: CDC commands 25 | 26 | * Interface 1: 27 | * Endpoint `0x01`: CDC data OUT 28 | * Endpoint `0x81`: CDC data IN 29 | 30 | * Interface Association: Vendor Specific Device Class 31 | * Interface 2: 32 | * Endpoint `0x03`: data OUT 33 | * Endpoint `0x83`: data IN 34 | 35 | The CDC interface (endpoint pair `0x01, 0x81`) runs the :ref:`ASCII Protocol ` by default (see :code:`odrv0.config.enable_ascii_protocol_on_usb`). 36 | The vendor specific interface (endpoint pair `0x03, 0x83`) runs the :ref:`Native Protocol ` (the packet based variant). 37 | 38 | The two interfaces can not (yet) be used simultaneously. 39 | -------------------------------------------------------------------------------- /tools/.gitignore: -------------------------------------------------------------------------------- 1 | 2 | # Python Distribution / packaging 3 | .Python 4 | #env/ 5 | #build/ 6 | #develop-eggs/ 7 | /dist/ 8 | #downloads/ 9 | #eggs/ 10 | #.eggs/ 11 | #lib/ 12 | #lib64/ 13 | #parts/ 14 | #sdist/ 15 | #var/ 16 | /*.egg-info/ 17 | #.installed.cfg 18 | #*.egg 19 | /MANIFEST 20 | 21 | # PyInstaller 22 | # Usually these files are written by a python script from a template 23 | # before PyInstaller builds the exe, so as to inject date/other infos into it. 24 | *.manifest 25 | *.spec 26 | 27 | # Installer logs 28 | pip-log.txt 29 | pip-delete-this-directory.txt 30 | -------------------------------------------------------------------------------- /tools/.vscode/launch.json: -------------------------------------------------------------------------------- 1 | { 2 | // Use IntelliSense to learn about possible attributes. 3 | // Hover to view descriptions of existing attributes. 4 | // For more information, visit: https://go.microsoft.com/fwlink/?linkid=830387 5 | "version": "0.2.0", 6 | "configurations": [ 7 | { 8 | "name": "Python", 9 | "type": "python", 10 | "request": "launch", 11 | "stopOnEntry": true, 12 | "python": "${command:python.pythonPath}", 13 | "program": "${file}", 14 | "cwd": "${workspaceRoot}", 15 | "env": {}, 16 | "envFile": "${workspaceRoot}/.env", 17 | "debugOptions": [ 18 | "WaitOnAbnormalExit", 19 | "WaitOnNormalExit", 20 | "RedirectOutput" 21 | ] 22 | } 23 | ] 24 | } -------------------------------------------------------------------------------- /tools/arduino_enums_template.j2: -------------------------------------------------------------------------------- 1 | 2 | #ifndef ODriveEnums_h 3 | #define ODriveEnums_h 4 | 5 | /* TODO: This file is dangerous because the enums could potentially change between API versions. Should transmit as part of the JSON. 6 | ** To regenerate this file, nagivate to the top level of the ODrive repository and run: 7 | ** python Firmware/interface_generator_stub.py --definitions Firmware/odrive-interface.yaml --template tools/arduino_enums_template.j2 --output Arduino/ODriveArduino/ODriveEnums.h 8 | */ 9 | 10 | [%- for _, enum in value_types.items() %] 11 | [%- if enum.is_enum %] 12 | 13 | // [[enum.fullname]] 14 | enum [[(enum.parent.name if enum.name in ['Error', 'Mode'] else '') + enum.name ]] { 15 | [%- for k, value in enum['values'].items() %] 16 | [[((((enum.parent.name if enum.name in ['Error', 'Mode'] else '') + enum.name) | to_macro_case) + "_" + (k | to_macro_case)).ljust(40)]] = [% if enum.is_flags %]0x[['%08x' | format(value.value)]][% else %][[value.value]][% endif %], 17 | [%- endfor %] 18 | }; 19 | [%- endif %] 20 | [%- endfor %] 21 | 22 | #endif 23 | 24 | -------------------------------------------------------------------------------- /tools/can_async_example.py: -------------------------------------------------------------------------------- 1 | import can 2 | 3 | bus1 = can.interface.Bus('can0', bustype='virtual') 4 | bus2 = can.interface.Bus('can0', bustype='virtual') 5 | 6 | msg1 = can.Message(arbitration_id=0xabcde, data=[1,2,3]) 7 | bus1.send(msg1) 8 | msg2 = bus2.recv() 9 | 10 | print(hex(msg1.arbitration_id)) 11 | print(hex(msg2.arbitration_id)) 12 | assert msg1.arbitration_id == msg2.arbitration_id -------------------------------------------------------------------------------- /tools/can_example.py: -------------------------------------------------------------------------------- 1 | import can 2 | 3 | bus = can.Bus("can0", bustype="socketcan") 4 | axisID = 0x1 5 | 6 | print("Requesting AXIS_STATE_FULL_CALIBRATION_SEQUENCE (0x03) on axisID: " + str(axisID)) 7 | msg = can.Message(arbitration_id=axisID << 5 | 0x07, data=[3, 0, 0, 0, 0, 0, 0, 0], dlc=8, is_extended_id=False) 8 | print(msg) 9 | 10 | try: 11 | bus.send(msg) 12 | print("Message sent on {}".format(bus.channel_info)) 13 | except can.CanError: 14 | print("Message NOT sent! Please verify can0 is working first") 15 | 16 | print("Waiting for calibration to finish...") 17 | # Read messages infinitely and wait for the right ID to show up 18 | while True: 19 | msg = bus.recv() 20 | if msg.arbitration_id == (axisID << 5 | 0x01): 21 | current_state = msg.data[4] 22 | if current_state == 0x1: 23 | print("\nAxis has returned to Idle state.") 24 | break 25 | 26 | for msg in bus: 27 | if(msg.arbitration_id == (axisID << 5 | 0x01)): 28 | errorCode = msg.data[0] | msg.data[1] << 8 | msg.data[2] << 16 | msg.data[3] << 24 29 | print("\nReceived Axis heartbeat message:") 30 | if errorCode == 0x0: 31 | print("No errors") 32 | else: 33 | print("Axis error! Error code: "+str(hex(errorCode))) 34 | break 35 | 36 | print("\nPutting axis",axisID,"into AXIS_STATE_CLOSED_LOOP_CONTROL (0x08)...") 37 | msg = can.Message(arbitration_id=axisID << 5 | 0x07, data=[8, 0, 0, 0, 0, 0, 0, 0], dlc=8, is_extended_id=False) 38 | print(msg) 39 | 40 | try: 41 | bus.send(msg) 42 | print("Message sent on {}".format(bus.channel_info)) 43 | except can.CanError: 44 | print("Message NOT sent!") 45 | 46 | for msg in bus: 47 | if msg.arbitration_id == (axisID << 5 | 0x01): 48 | print("\nReceived Axis heartbeat message:") 49 | if msg.data[4] == 0x8: 50 | print("Axis has entered closed loop") 51 | else: 52 | print("Axis failed to enter closed loop") 53 | break 54 | -------------------------------------------------------------------------------- /tools/enums_template.j2: -------------------------------------------------------------------------------- 1 | 2 | # TODO: This file is dangerous because the enums could potentially change between API versions. Should transmit as part of the JSON. 3 | # To regenerate this file, nagivate to the top level of the ODrive repository and run: 4 | # python Firmware/interface_generator_stub.py --definitions Firmware/odrive-interface.yaml --template tools/enums_template.j2 --output tools/odrive/enums.py 5 | 6 | import enum 7 | 8 | [%- for _, enum in value_types.items() %] 9 | [%- if enum.is_enum %] 10 | 11 | # [[enum.fullname]] 12 | [%- for k, value in enum['values'].items() %] 13 | [[((((enum.parent.name if enum.name in ['Error', 'Mode'] else '') + enum.name) | to_macro_case) + "_" + (k | to_macro_case)).ljust(40)]] = [% if enum.is_flags %]0x[['%08x' | format(value.value)]][% else %][[value.value]][% endif %] 14 | [%- endfor %] 15 | [%- endif %] 16 | [%- endfor %] 17 | 18 | [%- for _, enum in value_types.items() %] 19 | [%- if enum.is_enum %] 20 | class [[(enum.parent.name if enum.name in ['Error', 'Mode', 'Protocol'] else '') + enum.name]][% if enum.is_flags %](enum.IntFlag)[% else %](enum.Enum)[% endif %]: 21 | [%- for k, value in enum['values'].items() %] 22 | [[((k | to_macro_case)).ljust(40)]] = [% if enum.is_flags %]0x[['%08x' | format(value.value)]][% else %][[value.value]][% endif %] 23 | [%- endfor %] 24 | [%- endif %] 25 | [%- endfor %] 26 | -------------------------------------------------------------------------------- /tools/fibre-tools/fibre-shell: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | """ 3 | Connect to a Fibre-enabled device to play with in the IPython interactive shell. 4 | """ 5 | import argparse 6 | import sys 7 | import os 8 | 9 | sys.path.insert(0, os.path.dirname(os.path.dirname(os.path.realpath(__file__))) + "/python") 10 | 11 | from fibre import Logger, Event 12 | 13 | # Parse arguments 14 | parser = argparse.ArgumentParser(description='Connect to a fibre-enabled device to play with it in the IPython interactive shell.') 15 | parser.add_argument("-p", "--path", metavar="PATH", action="store", 16 | help="The path(s) where ODrive(s) should be discovered.\n" 17 | "By default the script will connect to any ODrive on USB.\n\n" 18 | "To select a specific USB device:\n" 19 | " --path usb:BUS:DEVICE\n" 20 | "usbwhere BUS and DEVICE are the bus and device numbers as shown in `lsusb`.\n\n" 21 | "To select a specific serial port:\n" 22 | " --path serial:PATH\n" 23 | "where PATH is the path of the serial port. For example \"/dev/ttyUSB0\".\n" 24 | "You can use `ls /dev/tty*` to find the correct port.\n\n" 25 | "You can combine USB and serial specs by separating them with a comma (no space!)\n" 26 | "Example:\n" 27 | " --path usb,serial:/dev/ttyUSB0\n" 28 | "means \"discover any USB device or a serial device on /dev/ttyUSB0\"") 29 | parser.add_argument("-s", "--serial-number", action="store", 30 | help="The 12-digit serial number of the device. " 31 | "This is a string consisting of 12 upper case hexadecimal " 32 | "digits as displayed in lsusb. \n" 33 | " example: 385F324D3037\n" 34 | "You can list all devices connected to USB by running\n" 35 | "(lsusb -d 1209:0d32 -v; lsusb -d 0483:df11 -v) | grep iSerial\n" 36 | "If omitted, any device is accepted.") 37 | parser.add_argument("--no-ipython", action="store_true", 38 | help="Use the regular Python shell " 39 | "instead of the IPython shell, " 40 | "even if IPython is installed.") 41 | parser.add_argument("-v", "--verbose", action="store_true", 42 | help="print debug information") 43 | 44 | parser.set_defaults(path="usb,tcp:localhost:9910") 45 | args = parser.parse_args() 46 | 47 | logger = Logger(verbose=args.verbose) 48 | 49 | def print_banner(): 50 | pass 51 | 52 | def print_help(args, have_devices): 53 | pass 54 | 55 | import fibre 56 | fibre.launch_shell(args, {}, print_banner, print_help, logger) 57 | -------------------------------------------------------------------------------- /tools/odrive/dfuse/COPYING: -------------------------------------------------------------------------------- 1 | 2 | The Python dfuse tool was written by Paul Liétar. 3 | Minor modifications were made for this project. 4 | Original source: https://github.com/plietar/dfuse-tool 5 | 6 | The license for this module is unclear. 7 | -------------------------------------------------------------------------------- /tools/odrive/dfuse/DfuFile.py: -------------------------------------------------------------------------------- 1 | import argparse 2 | import sys 3 | import struct 4 | import binascii 5 | 6 | def named(tuple,names): 7 | return dict(zip(names,tuple)) 8 | 9 | def parse(fmt,data,names): 10 | return named(struct.unpack(fmt,data),names) 11 | 12 | def fileunpack(f, fmt, names): 13 | n = struct.calcsize(fmt) 14 | return parse(fmt, f.read(n), names) 15 | 16 | class DfuFile: 17 | def __init__(self, path): 18 | self.targets = list() 19 | self.devInfo = dict() 20 | 21 | try: 22 | dfufile = open(path, 'rb') 23 | except: 24 | raise argparse.ArgumentTypeError('Could not open file %r' % path) 25 | 26 | with dfufile: 27 | 28 | header = fileunpack(dfufile, "<5sBLB", ('signature', 'version', 'size', 'targets')) 29 | 30 | if header['signature'] != b'DfuSe': 31 | raise argparse.ArgumentTypeError('File signature does not match') 32 | if header['version'] != 1: 33 | raise argparse.ArgumentTypeError('Unsupport DfuSe file version') 34 | 35 | for t in range(header['targets']): 36 | target_prefix = fileunpack(dfufile, "<6sBL255sLL", ('signature', 'alternate', 'named', 'name', 'size', 'elements')) 37 | if target_prefix['signature'] != b'Target': 38 | raise argparse.ArgumentTypeError('Target signature does not match') 39 | 40 | target = { 41 | 'name': target_prefix['name'].decode('ascii').rstrip('\0'), 42 | 'alternate': target_prefix['alternate'], 43 | 'elements': list() 44 | } 45 | 46 | for e in range(target_prefix['elements']): 47 | element_prefix = fileunpack(dfufile," 2 | 3 | 4 | Test Results 5 | 50 | 51 | 52 |

Test Results

53 |

Status: {{ status }}

54 |

This summary was generated on {{ date.isoformat() }}

55 | 56 | 57 | 58 | 59 | 60 | {% for name, test_cases in test_results %} 61 | 62 | 72 | 73 | 74 | {% endfor %} 75 |
TestResult
63 | {% if test_cases | fails | length %} 64 |
65 | {% elif test_cases | passes | length %} 66 |
67 | {% else %} 68 |
69 | {% endif %} 70 | {{name}} 71 |
{{test_cases | passes | length}} / {{test_cases | length}}
76 | 77 | 78 | -------------------------------------------------------------------------------- /tools/odrive/tests/run_all_tests.sh: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env bash 2 | set -euo pipefail 3 | 4 | declare -a tests=('analog_input_test.py' 5 | 'calibration_test.py' 6 | 'can_test.py' 7 | 'closed_loop_test.py' 8 | 'encoder_test.py' 9 | 'fibre_test.py' 10 | 'integration_test.py' 11 | 'nvm_test.py' 12 | 'pwm_input_test.py' 13 | 'sensor_test.py' 14 | 'step_dir_test.py' 15 | 'uart_ascii_test.py' 16 | ) 17 | summary="" 18 | 19 | for test in "${tests[@]}"; do 20 | (ipython3 "$test" || true) | tee /tmp/odrivetest.log 21 | if grep "All tests passed!" /tmp/odrivetest.log; then 22 | summary="$summary - $test: passed"$'\n' 23 | else 24 | summary="$summary - $test: failed"$'\n' 25 | fi 26 | 27 | echo "########################" 28 | echo "Current status:" 29 | echo -n "$summary" 30 | echo "########################" 31 | done 32 | -------------------------------------------------------------------------------- /tools/odrive_demo.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | """ 3 | Example usage of the ODrive python library to monitor and control ODrive devices 4 | """ 5 | 6 | from __future__ import print_function 7 | 8 | import odrive 9 | from odrive.enums import * 10 | import time 11 | import math 12 | 13 | # Find a connected ODrive (this will block until you connect one) 14 | print("finding an odrive...") 15 | my_drive = odrive.find_any() 16 | 17 | # Calibrate motor and wait for it to finish 18 | print("starting calibration...") 19 | my_drive.axis0.requested_state = AXIS_STATE_FULL_CALIBRATION_SEQUENCE 20 | while my_drive.axis0.current_state != AXIS_STATE_IDLE: 21 | time.sleep(0.1) 22 | 23 | my_drive.axis0.requested_state = AXIS_STATE_CLOSED_LOOP_CONTROL 24 | 25 | # To read a value, simply read the property 26 | print("Bus voltage is " + str(my_drive.vbus_voltage) + "V") 27 | 28 | # Or to change a value, just assign to the property 29 | my_drive.axis0.controller.input_pos = 3.14 30 | print("Position setpoint is " + str(my_drive.axis0.controller.pos_setpoint)) 31 | 32 | # And this is how function calls are done: 33 | for i in [1,2,3,4]: 34 | print('voltage on GPIO{} is {} Volt'.format(i, my_drive.get_adc_voltage(i))) 35 | 36 | # A sine wave to test 37 | t0 = time.monotonic() 38 | while True: 39 | setpoint = 4.0 * math.sin((time.monotonic() - t0)*2) 40 | print("goto " + str(int(setpoint))) 41 | my_drive.axis0.controller.input_pos = setpoint 42 | time.sleep(0.01) 43 | 44 | # Some more things you can try: 45 | 46 | # Write to a read-only property: 47 | my_drive.vbus_voltage = 11.0 # fails with `AttributeError: can't set attribute` 48 | 49 | # Assign an incompatible value: 50 | my_drive.motor0.pos_setpoint = "I like trains" # fails with `ValueError: could not convert string to float` 51 | -------------------------------------------------------------------------------- /tools/odrive_header_template.h.in: -------------------------------------------------------------------------------- 1 | /* 2 | * This file was autogenerated using the "odrivetool generate-code" feature. 3 | * 4 | * The file matches a specific firmware version. If you add/remove/rename any 5 | * properties exposed by the ODrive, this file needs to be regenerated, otherwise 6 | * the ODrive will ignore all commands. 7 | */ 8 | 9 | #ifndef __ODRIVE_ENDPOINTS_HPP 10 | #define __ODRIVE_ENDPOINTS_HPP 11 | {% macro enum_name(endpoint) %}{{ endpoint.name | replace('.', '__') | upper }}{% endmacro %} 12 | 13 | namespace odrive { 14 | 15 | static constexpr const uint16_t json_crc = 0x{{ "%0x" | format(json_crc) }}; 16 | 17 | static constexpr const uint16_t per_axis_offset = {{ per_axis_offset }}; 18 | 19 | enum { {% for endpoint in endpoints %} 20 | {{enum_name(endpoint)}} = {{endpoint.id}}, 21 | {%- endfor %} 22 | 23 | // Per-Axis endpoints (to be used with read_axis_property and write_axis_property) 24 | {%- for endpoint in axis_endpoints %} 25 | {{enum_name(endpoint)}} = {{endpoint.id}}, 26 | {%- endfor %} 27 | }; 28 | 29 | template 30 | struct endpoint_type; 31 | 32 | {% for endpoint in endpoints -%} 33 | template<> struct endpoint_type<{{enum_name(endpoint)}}> { typedef {{endpoint.type}} type; }; 34 | {% endfor %} 35 | 36 | // Per-axis endpoints 37 | {% for endpoint in axis_endpoints -%} 38 | template<> struct endpoint_type<{{enum_name(endpoint)}}> { typedef {{endpoint.type}} type; }; 39 | {% endfor %} 40 | 41 | template 42 | using endpoint_type_t = typename endpoint_type::type; 43 | 44 | } 45 | 46 | #endif // __ODRIVE_ENDPOINTS_HPP 47 | -------------------------------------------------------------------------------- /tools/odrivetool.bat: -------------------------------------------------------------------------------- 1 | @echo off 2 | ipython "%~dp0\odrivetool" -- %* 3 | -------------------------------------------------------------------------------- /tools/plot_oscilloscope.py: -------------------------------------------------------------------------------- 1 | 2 | from matplotlib import pyplot as plt 3 | import sys 4 | 5 | with open(sys.argv[1]) as f: 6 | data = list(map(float, f)) 7 | 8 | plt.plot(data) 9 | plt.show() -------------------------------------------------------------------------------- /tools/requirements.txt: -------------------------------------------------------------------------------- 1 | --index-url https://pypi.python.org/simple/ 2 | 3 | -e . -------------------------------------------------------------------------------- /tools/test-rig-jw.yaml: -------------------------------------------------------------------------------- 1 | 2 | components: 3 | - type: generalpurpose 4 | name: homenet 5 | net: homenet 6 | 7 | - type: generalpurpose 8 | name: rpi 9 | ssh: odrv 10 | net: homenet 11 | components: 12 | - type: can 13 | name: can0 14 | interface: can0 15 | path: /dev/serial/by-id/usb-Protofusion_Labs_CANable_1205aa6_https:__github.com_normaldotcom_cantact-fw_002080015852430220363530-if00 16 | connected-to: odrive.can 17 | 18 | - type: odrive 19 | name: odrive-v4_1 20 | board-version: v4.1-58V 21 | serial-number: "2060307C4E53" 22 | encoder0: virtual_encoder0 23 | motor0: D6374_150KV_0 24 | 25 | - type: odrive 26 | name: odrive-v4_0 27 | board-version: v4.0-58V 28 | serial-number: "206730834E53" # smart motor 29 | encoder0: virtual_encoder1 30 | motor0: D6374_150KV_1 31 | 32 | - type: motor 33 | name: D6374_150KV_0 34 | phase-resistance: 0.065 35 | phase-inductance: 2.15e-05 36 | 37 | - type: motor 38 | name: D6374_150KV_1 39 | phase-resistance: 0.065 40 | phase-inductance: 2.15e-05 41 | 42 | - type: encoder 43 | name: quadrature_encoder0 44 | cpr: 8192 45 | max-rpm: 7000 46 | 47 | - type: encoder 48 | name: quadrature_encoder1 49 | cpr: 8192 50 | max-rpm: 7000 51 | 52 | connections: 53 | - ['odrive-v4_1.can', 'rpi.can0'] 54 | - ['odrive-v4_1.axis0', 'D6374_150KV_0.phases'] 55 | - ['odrive-v4_0.axis0', 'D6374_150KV_1.phases'] 56 | - ['quadrature_encoder0.shaft', 'D6374_150KV_0.shaft', 'D6374_150KV_1.shaft', 'quadrature_encoder1.shaft'] 57 | - ['odrive-v4_1.encoder0.a', 'quadrature_encoder0.a'] 58 | - ['odrive-v4_1.encoder0.b', 'quadrature_encoder0.b'] 59 | - ['odrive-v4_1.encoder0.z', 'quadrature_encoder0.z'] 60 | - ['odrive-v4_0.encoder0.a', 'quadrature_encoder1.a'] 61 | - ['odrive-v4_0.encoder0.b', 'quadrature_encoder1.b'] 62 | - ['odrive-v4_0.encoder0.z', 'quadrature_encoder1.z'] 63 | -------------------------------------------------------------------------------- /tools/test-rig-loopback.yaml: -------------------------------------------------------------------------------- 1 | 2 | type: loopback 3 | 4 | odrives: 5 | - name: odrv-blackside 6 | board-version: v3.4-24V 7 | serial-number: "3061395B3235" 8 | brake-resistance: 0.47 9 | uart: /dev/serial/by-id/[not-yet-used] 10 | usb: auto 11 | programmer: '\x49\x3f\x6f\x06\x49\x3f\x56\x54\x09\x29\x11\x3f' 12 | vbus-voltage: 24 # [V] 13 | max-brake-power: 150 # [W] 14 | axes: 15 | - name: 'M0' 16 | motor-phase-resistance: 0.028 17 | motor-phase-inductance: 1.6e-05 18 | motor-pole-pairs: 7 19 | motor-direction: 1 20 | motor-kv: 270 21 | motor-max-current: 70 22 | motor-max-voltage: 32 23 | encoder-cpr: 8192 24 | encoder-max-rpm: 7000 25 | - name: 'M1' 26 | motor-phase-resistance: 0.028 27 | motor-phase-inductance: 1.6e-05 28 | motor-pole-pairs: 7 29 | motor-direction: -1 30 | motor-kv: 270 31 | motor-max-current: 70 32 | motor-max-voltage: 32 33 | encoder-cpr: 8192 34 | encoder-max-rpm: 7000 35 | - name: odrv-yellowside 36 | board-version: v3.5-48V 37 | serial-number: "3660335E3037" 38 | brake-resistance: 0.47 39 | uart: /dev/serial/by-id/[not-yet-used] 40 | usb: auto 41 | programmer: '\x53\x3f\x75\x06\x49\x3f\x49\x51\x44\x54\x19\x3f' 42 | vbus-voltage: 48 # [V] 43 | max-brake-power: 150 # [W] 44 | axes: 45 | - name: 'M0' 46 | motor-phase-resistance: 0.0245 47 | motor-phase-inductance: 2.03e-05 48 | motor-pole-pairs: 7 49 | motor-direction: 1 50 | motor-kv: 190 51 | motor-max-current: 70 52 | motor-max-voltage: 40 53 | encoder-cpr: 8192 54 | encoder-max-rpm: 7000 55 | - name: 'M1' 56 | motor-phase-resistance: 0.0245 57 | motor-phase-inductance: 2.03e-05 58 | motor-pole-pairs: 7 59 | motor-direction: -1 60 | motor-kv: 190 61 | motor-max-current: 70 62 | motor-max-voltage: 40 63 | encoder-cpr: 8192 64 | encoder-max-rpm: 7000 65 | 66 | # Mechanical couplings 67 | couplings: 68 | - [ odrv-blackside.M0, odrv-blackside.M1 ] 69 | - [ odrv-yellowside.M0, odrv-yellowside.M1 ] -------------------------------------------------------------------------------- /tools/test-rig-parallel.yaml: -------------------------------------------------------------------------------- 1 | 2 | type: parallel 3 | 4 | # ODrives 5 | odrives: 6 | - name: top-odrive 7 | board-version: v3.5-48V 8 | serial-number: "3660335E3037" 9 | brake-resistance: 0.47 10 | uart: /dev/serial/by-id/[not-yet-used] 11 | usb: auto 12 | programmer: '\x53\x3f\x75\x06\x49\x3f\x49\x51\x44\x54\x19\x3f' 13 | vbus-voltage: 24 # [V] 14 | max-brake-power: 150 # [W] 15 | axes: 16 | - name: 'yellow' 17 | motor-phase-resistance: 0.0245 18 | motor-phase-inductance: 2.03e-05 19 | motor-pole-pairs: 7 20 | motor-direction: 1 21 | motor-kv: 190 22 | motor-max-current: 70 23 | motor-max-voltage: 40 24 | encoder-cpr: 8192 25 | encoder-max-rpm: 7000 26 | - name: 'black' 27 | motor-phase-resistance: 0.028 28 | motor-phase-inductance: 1.6e-05 29 | motor-pole-pairs: 7 30 | motor-direction: -1 31 | motor-kv: 270 32 | motor-max-current: 70 33 | motor-max-voltage: 32 34 | encoder-cpr: 8192 35 | encoder-max-rpm: 7000 36 | - name: bottom-odrive 37 | board-version: v3.5-24V 38 | serial-number: "3661335E3037" 39 | brake-resistance: 0.47 40 | uart: /dev/serial/by-id/[not-yet-used] 41 | usb: auto 42 | programmer: '\x49\x3f\x6f\x06\x49\x3f\x56\x54\x09\x29\x11\x3f' 43 | vbus-voltage: 24 # [V] 44 | max-brake-power: 150 # [W] 45 | axes: 46 | - name: 'black' 47 | motor-phase-resistance: 0.028 48 | motor-phase-inductance: 1.6e-05 49 | motor-pole-pairs: 7 50 | motor-direction: 1 51 | motor-kv: 270 52 | motor-max-current: 70 53 | motor-max-voltage: 32 54 | encoder-cpr: 8192 55 | encoder-max-rpm: 7000 56 | - name: 'yellow' 57 | motor-phase-resistance: 0.0245 58 | motor-phase-inductance: 2.03e-05 59 | motor-pole-pairs: 7 60 | motor-direction: -1 61 | motor-kv: 190 62 | motor-max-current: 70 63 | motor-max-voltage: 40 64 | encoder-cpr: 8192 65 | encoder-max-rpm: 7000 66 | 67 | # Mechanical couplings 68 | couplings: 69 | - [ top-odrive.yellow, bottom-odrive.yellow ] 70 | - [ top-odrive.black, bottom-odrive.black ] 71 | -------------------------------------------------------------------------------- /tools/usbpermission: -------------------------------------------------------------------------------- 1 | sudo udevadm control --reload-rules && sudo service udev restart && sudo udevadm trigger 2 | --------------------------------------------------------------------------------