mirror of
https://github.com/odriverobotics/ODrive.git
synced 2026-02-06 07:01:52 +08:00
Merge branch 'devel' into libfibre
This commit is contained in:
9
.github/workflows/nightly.yaml
vendored
9
.github/workflows/nightly.yaml
vendored
@@ -15,13 +15,16 @@ jobs:
|
||||
runs-on: ${{ matrix.os }}
|
||||
steps:
|
||||
- name: Install odrivetool
|
||||
shell: bash
|
||||
run: |
|
||||
pip3 list | grep setuptools || echo "setuptools not installed" # show version
|
||||
pip3 install setuptools # TODO: this should be a dependency of odrive
|
||||
pip3 install odrive
|
||||
env:
|
||||
# TODO: this is a workaround for https://github.com/pypa/setuptools/issues/2353 and we
|
||||
# can remove it as soon as python3-setuptools on GitHub's ubuntu-latest
|
||||
# moves to version 50.1+.
|
||||
pip3 list | grep setuptools # show version
|
||||
export SETUPTOOLS_USE_DISTUTILS=stdlib
|
||||
pip3 install odrive
|
||||
SETUPTOOLS_USE_DISTUTILS: stdlib
|
||||
|
||||
# This one currently fails because Github Actions runs pip as non-root
|
||||
#- name: Check if udev rules were set up properly
|
||||
|
||||
@@ -1,6 +1,7 @@
|
||||
# Unreleased Features
|
||||
Please add a note of your changes below this heading if you make a Pull Request.
|
||||
### Added
|
||||
* Added phase balance check to motor calibration and MOTOR_ERROR_UNBALANCED_PHASES to error enums
|
||||
* Added polarity and phase offset calibration for hall effect encoders
|
||||
* [Mechanical brake support](docs/mechanical-brakes.md)
|
||||
* Added periodic sending of encoder position on CAN
|
||||
@@ -61,6 +62,7 @@ Please add a note of your changes below this heading if you make a Pull Request.
|
||||
* `<axis>.encoder.config.offset` was renamed to ``<axis>.encoder.config.phase_offset`
|
||||
* `<axis>.encoder.config.offset_float` was renamed to ``<axis>.encoder.config.phase_offset_float`
|
||||
* `<odrv>.config.brake_resistance == 0.0` is no longer a valid way to disable the brake resistor. Use `<odrv>.config.enable_brake_resistor` instead.
|
||||
* `<odrv>.can.set_baud_rate()` was removed. The baudrate is now automatically updated when writing to `<odrv>.can.config.baud_rate`.
|
||||
|
||||
# Releases
|
||||
## [0.5.1] - 2020-09-27
|
||||
|
||||
@@ -56,31 +56,46 @@
|
||||
|
||||
/* USER CODE END 0 */
|
||||
|
||||
CAN_HandleTypeDef hcan1;
|
||||
CAN_HandleTypeDef hcan1 = {
|
||||
.Instance = CAN1,
|
||||
.Init = {
|
||||
.Prescaler = 8,
|
||||
.Mode = CAN_MODE_NORMAL,
|
||||
.SyncJumpWidth = CAN_SJW_4TQ,
|
||||
.TimeSeg1 = CAN_BS1_16TQ,
|
||||
.TimeSeg2 = CAN_BS2_4TQ,
|
||||
.TimeTriggeredMode = DISABLE,
|
||||
.AutoBusOff = ENABLE,
|
||||
.AutoWakeUp = ENABLE,
|
||||
.AutoRetransmission = ENABLE,
|
||||
.ReceiveFifoLocked = DISABLE,
|
||||
.TransmitFifoPriority = DISABLE,
|
||||
}
|
||||
};
|
||||
|
||||
/* CAN1 init function */
|
||||
void MX_CAN1_Init(void)
|
||||
{
|
||||
|
||||
hcan1.Instance = CAN1;
|
||||
hcan1.Init.Prescaler = 8;
|
||||
hcan1.Init.Mode = CAN_MODE_NORMAL;
|
||||
hcan1.Init.SyncJumpWidth = CAN_SJW_4TQ;
|
||||
hcan1.Init.TimeSeg1 = CAN_BS1_16TQ;
|
||||
hcan1.Init.TimeSeg2 = CAN_BS2_4TQ;
|
||||
hcan1.Init.TimeTriggeredMode = DISABLE;
|
||||
hcan1.Init.AutoBusOff = ENABLE;
|
||||
hcan1.Init.AutoWakeUp = ENABLE;
|
||||
hcan1.Init.AutoRetransmission = ENABLE;
|
||||
hcan1.Init.ReceiveFifoLocked = DISABLE;
|
||||
hcan1.Init.TransmitFifoPriority = DISABLE;
|
||||
if (HAL_CAN_Init(&hcan1) != HAL_OK)
|
||||
{
|
||||
_Error_Handler(__FILE__, __LINE__);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
//void MX_CAN1_Init(void)
|
||||
//{
|
||||
//
|
||||
// hcan1.Instance = CAN1;
|
||||
// hcan1.Init.Prescaler = 8;
|
||||
// hcan1.Init.Mode = CAN_MODE_NORMAL;
|
||||
// hcan1.Init.SyncJumpWidth = CAN_SJW_4TQ;
|
||||
// hcan1.Init.TimeSeg1 = CAN_BS1_16TQ;
|
||||
// hcan1.Init.TimeSeg2 = CAN_BS2_4TQ;
|
||||
// hcan1.Init.TimeTriggeredMode = DISABLE;
|
||||
// hcan1.Init.AutoBusOff = ENABLE;
|
||||
// hcan1.Init.AutoWakeUp = ENABLE;
|
||||
// hcan1.Init.AutoRetransmission = ENABLE;
|
||||
// hcan1.Init.ReceiveFifoLocked = DISABLE;
|
||||
// hcan1.Init.TransmitFifoPriority = DISABLE;
|
||||
// if (HAL_CAN_Init(&hcan1) != HAL_OK)
|
||||
// {
|
||||
// _Error_Handler(__FILE__, __LINE__);
|
||||
// }
|
||||
//
|
||||
//}
|
||||
//
|
||||
void HAL_CAN_MspInit(CAN_HandleTypeDef* canHandle)
|
||||
{
|
||||
|
||||
|
||||
@@ -101,13 +101,18 @@ void HAL_SPI_MspInit(SPI_HandleTypeDef* spiHandle)
|
||||
PC11 ------> SPI3_MISO
|
||||
PC12 ------> SPI3_MOSI
|
||||
*/
|
||||
GPIO_InitStruct.Pin = GPIO_PIN_10|GPIO_PIN_11|GPIO_PIN_12;
|
||||
GPIO_InitStruct.Pin = GPIO_PIN_10|GPIO_PIN_12;
|
||||
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
|
||||
GPIO_InitStruct.Pull = GPIO_PULLUP; // required for disconnect detection on SPI encoders
|
||||
GPIO_InitStruct.Pull = GPIO_PULLDOWN; // Idle clock and MOSI low.
|
||||
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH;
|
||||
GPIO_InitStruct.Alternate = GPIO_AF6_SPI3;
|
||||
HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
|
||||
|
||||
// MISO pull-up required for disconnect detection on SPI encoders with even parity
|
||||
GPIO_InitStruct.Pin = GPIO_PIN_11;
|
||||
GPIO_InitStruct.Pull = GPIO_PULLUP;
|
||||
HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
|
||||
|
||||
/* SPI3 DMA Init */
|
||||
/* SPI3_TX Init */
|
||||
hdma_spi3_tx.Instance = DMA1_Stream7;
|
||||
|
||||
@@ -357,8 +357,6 @@ bool board_init() {
|
||||
// mode initialization won't override the CAN mode.
|
||||
if (odrv.config_.gpio_modes[15] != ODriveIntf::GPIO_MODE_CAN_A || odrv.config_.gpio_modes[16] != ODriveIntf::GPIO_MODE_CAN_A) {
|
||||
odrv.misconfigured_ = true;
|
||||
} else {
|
||||
MX_CAN1_Init();
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -36,6 +36,7 @@ bool Stm32SpiArbiter::start() {
|
||||
HAL_SPI_DeInit(hspi_);
|
||||
hspi_->Init = task.config;
|
||||
HAL_SPI_Init(hspi_);
|
||||
__HAL_SPI_ENABLE(hspi_);
|
||||
}
|
||||
task.ncs_gpio.write(false);
|
||||
|
||||
|
||||
@@ -9,8 +9,14 @@ PROGRAMMER_CMD=$(if $(value PROGRAMMER),-c 'hla_serial $(PROGRAMMER)',)
|
||||
|
||||
include tup.config # source build configuration to get CONFIG_BOARD_VERSION
|
||||
|
||||
ifeq ($(shell python -c "import sys; print(sys.version_info.major)"), 3)
|
||||
PY_CMD := python -B
|
||||
else
|
||||
PY_CMD := python3 -B
|
||||
endif
|
||||
|
||||
ifneq (,$(findstring v3.,$(CONFIG_BOARD_VERSION)))
|
||||
OPENOCD := openocd -f interface/stlink.cfg $(PROGRAMMER_CMD) -f target/stm32f4x.cfg -c init
|
||||
OPENOCD := openocd -f interface/stlink-v2.cfg $(PROGRAMMER_CMD) -f target/stm32f4x.cfg -c init
|
||||
GDB := arm-none-eabi-gdb --ex 'target extended-remote | openocd -f "interface/stlink-v2.cfg" -f "target/stm32f4x.cfg" -c "gdb_port pipe; log_output openocd.log"' --ex 'monitor reset halt'
|
||||
else ifneq (,$(findstring v4.,$(CONFIG_BOARD_VERSION)))
|
||||
OPENOCD := openocd -f interface/stlink.cfg $(PROGRAMMER_CMD) -f target/stm32f7x.cfg -c 'reset_config none separate' -c init
|
||||
@@ -23,7 +29,7 @@ $(info board version: $(CONFIG_BOARD_VERSION))
|
||||
|
||||
all:
|
||||
@tup --quiet --no-environ-check
|
||||
@python interface_generator_stub.py --definitions odrive-interface.yaml --template ../tools/enums_template.j2 --output ../tools/odrive/enums.py
|
||||
@$(PY_CMD) interface_generator_stub.py --definitions odrive-interface.yaml --template ../tools/enums_template.j2 --output ../tools/odrive/enums.py
|
||||
|
||||
fibre:
|
||||
(cd fibre-cpp && tup --no-environ-check)
|
||||
|
||||
@@ -313,14 +313,18 @@ bool Axis::start_closed_loop_control() {
|
||||
motor_.current_control_.Idq_setpoint_src_.connect_to(&motor_.Idq_setpoint_);
|
||||
motor_.current_control_.Vdq_setpoint_src_.connect_to(&motor_.Vdq_setpoint_);
|
||||
|
||||
bool is_acim = motor_.config_.motor_type == Motor::MOTOR_TYPE_ACIM;
|
||||
// phase
|
||||
OutputPort<float>* phase_src = sensorless_mode ? &sensorless_estimator_.phase_ : &encoder_.phase_;
|
||||
motor_.current_control_.phase_src_.connect_to(phase_src);
|
||||
acim_estimator_.rotor_phase_src_.connect_to(phase_src);
|
||||
|
||||
OutputPort<float>* stator_phase_src = is_acim ? &acim_estimator_.stator_phase_ : phase_src;
|
||||
motor_.current_control_.phase_src_.connect_to(stator_phase_src);
|
||||
// phase vel
|
||||
OutputPort<float>* phase_vel_src = sensorless_mode ? &sensorless_estimator_.phase_vel_ : &encoder_.phase_vel_;
|
||||
motor_.phase_vel_src_.connect_to(phase_vel_src);
|
||||
motor_.current_control_.phase_vel_src_.connect_to(phase_vel_src);
|
||||
acim_estimator_.rotor_phase_vel_src_.connect_to(phase_vel_src);
|
||||
OutputPort<float>* stator_phase_vel_src = is_acim ? &acim_estimator_.stator_phase_vel_ : phase_vel_src;
|
||||
motor_.phase_vel_src_.connect_to(stator_phase_vel_src);
|
||||
motor_.current_control_.phase_vel_src_.connect_to(stator_phase_vel_src);
|
||||
|
||||
if (sensorless_mode) {
|
||||
// Make the final velocity of the loĉk-in spin the setpoint of the
|
||||
|
||||
@@ -187,7 +187,6 @@ public:
|
||||
AxisState requested_state_ = AXIS_STATE_STARTUP_SEQUENCE;
|
||||
std::array<AxisState, 10> task_chain_ = { AXIS_STATE_UNDEFINED };
|
||||
AxisState& current_state_ = task_chain_.front();
|
||||
uint32_t loop_counter_ = 0;
|
||||
Homing_t homing_;
|
||||
CAN_t can_;
|
||||
|
||||
|
||||
@@ -1,7 +1,9 @@
|
||||
#ifndef __ENCODER_HPP
|
||||
#define __ENCODER_HPP
|
||||
|
||||
#include <arm_math.h>
|
||||
class Encoder;
|
||||
|
||||
#include <board.h> // needed for arm_math.h
|
||||
#include <Drivers/STM32/stm32_spi_arbiter.hpp>
|
||||
#include "utils.hpp"
|
||||
#include <autogen/interfaces.hpp>
|
||||
|
||||
@@ -26,8 +26,6 @@ uint32_t _reboot_cookie __attribute__ ((section (".noinit")));
|
||||
extern char _estack; // provided by the linker script
|
||||
|
||||
|
||||
ODriveCAN::Config_t can_config;
|
||||
ODriveCAN *odCAN = nullptr;
|
||||
ODrive odrv{};
|
||||
|
||||
|
||||
@@ -88,7 +86,7 @@ void StatusLedController::update() {
|
||||
static bool config_read_all() {
|
||||
bool success = board_read_config() &&
|
||||
config_manager.read(&odrv.config_) &&
|
||||
config_manager.read(&can_config);
|
||||
config_manager.read(&odrv.can_.config_);
|
||||
for (size_t i = 0; (i < AXIS_COUNT) && success; ++i) {
|
||||
success = config_manager.read(&encoders[i].config_) &&
|
||||
config_manager.read(&axes[i].sensorless_estimator_.config_) &&
|
||||
@@ -108,7 +106,7 @@ static bool config_read_all() {
|
||||
static bool config_write_all() {
|
||||
bool success = board_write_config() &&
|
||||
config_manager.write(&odrv.config_) &&
|
||||
config_manager.write(&can_config);
|
||||
config_manager.write(&odrv.can_.config_);
|
||||
for (size_t i = 0; (i < AXIS_COUNT) && success; ++i) {
|
||||
success = config_manager.write(&encoders[i].config_) &&
|
||||
config_manager.write(&axes[i].sensorless_estimator_.config_) &&
|
||||
@@ -127,7 +125,7 @@ static bool config_write_all() {
|
||||
|
||||
static void config_clear_all() {
|
||||
odrv.config_ = {};
|
||||
can_config = {};
|
||||
odrv.can_.config_ = {};
|
||||
for (size_t i = 0; i < AXIS_COUNT; ++i) {
|
||||
encoders[i].config_ = {};
|
||||
axes[i].sensorless_estimator_.config_ = {};
|
||||
@@ -145,7 +143,7 @@ static void config_clear_all() {
|
||||
}
|
||||
|
||||
static bool config_apply_all() {
|
||||
bool success = true;
|
||||
bool success = odrv.can_.apply_config();
|
||||
for (size_t i = 0; (i < AXIS_COUNT) && success; ++i) {
|
||||
success = encoders[i].apply_config(motors[i].config_.motor_type)
|
||||
&& axes[i].controller_.apply_config()
|
||||
@@ -174,6 +172,12 @@ bool ODrive::save_configuration(void) {
|
||||
&& config_manager.start_store(&config_size)
|
||||
&& config_write_all()
|
||||
&& config_manager.finish_store();
|
||||
|
||||
// FIXME: during save_configuration we might miss some interrupts
|
||||
// because the CPU gets halted during a flash erase. Missing events
|
||||
// (encoder updates, step/dir steps) is not good so to be sure we just
|
||||
// reboot.
|
||||
NVIC_SystemReset();
|
||||
}
|
||||
|
||||
return success;
|
||||
@@ -265,24 +269,23 @@ void vApplicationIdleHook(void) {
|
||||
odrv.system_stats_.max_stack_usage_usb = stack_size_usb_thread - uxTaskGetStackHighWaterMark(usb_thread) * sizeof(StackType_t);
|
||||
odrv.system_stats_.max_stack_usage_uart = stack_size_uart_thread - uxTaskGetStackHighWaterMark(uart_thread) * sizeof(StackType_t);
|
||||
odrv.system_stats_.max_stack_usage_startup = stack_size_default_task - uxTaskGetStackHighWaterMark(defaultTaskHandle) * sizeof(StackType_t);
|
||||
odrv.system_stats_.max_stack_usage_can = odCAN->stack_size_ - uxTaskGetStackHighWaterMark(odCAN->thread_id_) * sizeof(StackType_t);
|
||||
odrv.system_stats_.max_stack_usage_can = odrv.can_.stack_size_ - uxTaskGetStackHighWaterMark(odrv.can_.thread_id_) * sizeof(StackType_t);
|
||||
|
||||
odrv.system_stats_.stack_size_axis = axes[0].stack_size_;
|
||||
odrv.system_stats_.stack_size_usb = stack_size_usb_thread;
|
||||
odrv.system_stats_.stack_size_uart = stack_size_uart_thread;
|
||||
odrv.system_stats_.stack_size_startup = stack_size_default_task;
|
||||
odrv.system_stats_.stack_size_can = odCAN->stack_size_;
|
||||
odrv.system_stats_.stack_size_can = odrv.can_.stack_size_;
|
||||
|
||||
odrv.system_stats_.prio_axis = osThreadGetPriority(axes[0].thread_id_);
|
||||
odrv.system_stats_.prio_usb = osThreadGetPriority(usb_thread);
|
||||
odrv.system_stats_.prio_uart = osThreadGetPriority(uart_thread);
|
||||
odrv.system_stats_.prio_startup = osThreadGetPriority(defaultTaskHandle);
|
||||
odrv.system_stats_.prio_can = osThreadGetPriority(odCAN->thread_id_);
|
||||
odrv.system_stats_.prio_can = osThreadGetPriority(odrv.can_.thread_id_);
|
||||
|
||||
status_led_controller.update();
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -431,9 +434,6 @@ void ODrive::control_loop_cb(uint32_t timestamp) {
|
||||
axis.max_endstop_.update();
|
||||
}
|
||||
|
||||
MEASURE_TIME(axis.task_times_.can_heartbeat)
|
||||
odCAN->send_cyclic(axis);
|
||||
|
||||
MEASURE_TIME(axis.task_times_.controller_update)
|
||||
axis.controller_.update(); // uses position and velocity from encoder
|
||||
|
||||
@@ -827,9 +827,6 @@ extern "C" int main(void) {
|
||||
sem_can = osSemaphoreCreate(osSemaphore(sem_can), 1);
|
||||
osSemaphoreWait(sem_can, 0);
|
||||
|
||||
// Construct all objects.
|
||||
odCAN = new ODriveCAN(can_config, &hcan1);
|
||||
|
||||
// Create main thread
|
||||
osThreadDef(defaultTask, rtos_main, osPriorityNormal, 0, stack_size_default_task / sizeof(StackType_t));
|
||||
defaultTaskHandle = osThreadCreate(osThread(defaultTask), NULL);
|
||||
|
||||
@@ -6,8 +6,8 @@
|
||||
|
||||
#include <algorithm>
|
||||
|
||||
#define CURRENT_ADC_LOWER_BOUND (uint32_t)((float)(1 << 12) * CURRENT_SENSE_MIN_VOLT / 3.3f)
|
||||
#define CURRENT_ADC_UPPER_BOUND (uint32_t)((float)(1 << 12) * CURRENT_SENSE_MAX_VOLT / 3.3f)
|
||||
static constexpr auto CURRENT_ADC_LOWER_BOUND = (uint32_t)((float)(1 << 12) * CURRENT_SENSE_MIN_VOLT / 3.3f);
|
||||
static constexpr auto CURRENT_ADC_UPPER_BOUND = (uint32_t)((float)(1 << 12) * CURRENT_SENSE_MAX_VOLT / 3.3f);
|
||||
|
||||
/**
|
||||
* @brief This control law adjusts the output voltage such that a predefined
|
||||
@@ -29,6 +29,7 @@ struct ResistanceMeasurementControlLaw : AlphaBetaFrameController {
|
||||
if (Ialpha_beta.has_value()) {
|
||||
actual_current_ = Ialpha_beta->first;
|
||||
test_voltage_ += (kI * current_meas_period) * (target_current_ - actual_current_);
|
||||
I_beta_ += (kIBetaFilt * current_meas_period) * (Ialpha_beta->second - I_beta_);
|
||||
} else {
|
||||
actual_current_ = 0.0f;
|
||||
test_voltage_ = 0.0f;
|
||||
@@ -63,11 +64,17 @@ struct ResistanceMeasurementControlLaw : AlphaBetaFrameController {
|
||||
return test_voltage_ / target_current_;
|
||||
}
|
||||
|
||||
float get_Ibeta() {
|
||||
return I_beta_;
|
||||
}
|
||||
|
||||
const float kI = 1.0f; // [(V/s)/A]
|
||||
const float kIBetaFilt = 80.0f;
|
||||
float max_voltage_ = 0.0f;
|
||||
float actual_current_ = 0.0f;
|
||||
float target_current_ = 0.0f;
|
||||
float test_voltage_ = 0.0f;
|
||||
float I_beta_ = 0.0f; // [A] low pass filtered Ibeta response
|
||||
std::optional<float> test_mod_ = NAN;
|
||||
};
|
||||
|
||||
@@ -325,7 +332,7 @@ bool Motor::setup() {
|
||||
max_dc_calib_ = 0.1f * max_allowed_current_;
|
||||
|
||||
if (!gate_driver_.init())
|
||||
return true;
|
||||
return false;
|
||||
|
||||
return true;
|
||||
}
|
||||
@@ -435,6 +442,12 @@ bool Motor::measure_phase_resistance(float test_current, float max_voltage) {
|
||||
success = false;
|
||||
}
|
||||
|
||||
float I_beta = control_law.get_Ibeta();
|
||||
if (is_nan(I_beta) || (abs(I_beta) / test_current) > 0.1f) {
|
||||
disarm_with_error(ERROR_UNBALANCED_PHASES);
|
||||
success = false;
|
||||
}
|
||||
|
||||
return success;
|
||||
}
|
||||
|
||||
|
||||
@@ -122,9 +122,6 @@ struct TaskTimes {
|
||||
// Forward Declarations
|
||||
class Axis;
|
||||
class Motor;
|
||||
class ODriveCAN;
|
||||
|
||||
extern ODriveCAN *odCAN;
|
||||
|
||||
// TODO: move
|
||||
// this is technically not thread-safe but practically it might be
|
||||
@@ -153,6 +150,7 @@ inline ENUMTYPE operator ~ (ENUMTYPE a) { return static_cast<ENUMTYPE>(~static_c
|
||||
#include <axis.hpp>
|
||||
#include <oscilloscope.hpp>
|
||||
#include <communication/communication.h>
|
||||
#include <communication/can/odrive_can.hpp>
|
||||
|
||||
// Defined in autogen/version.c based on git-derived version numbers
|
||||
extern "C" {
|
||||
@@ -190,7 +188,6 @@ public:
|
||||
void control_loop_cb(uint32_t timestamp);
|
||||
|
||||
Axis& get_axis(int num) { return axes[num]; }
|
||||
ODriveCAN& get_can() { return *odCAN; }
|
||||
|
||||
uint32_t get_interrupt_status(int32_t irqn);
|
||||
uint32_t get_dma_status(uint8_t stream_num);
|
||||
@@ -229,6 +226,8 @@ public:
|
||||
nullptr // data_src TODO: change data type
|
||||
};
|
||||
|
||||
ODriveCAN can_;
|
||||
|
||||
BoardConfig_t config_;
|
||||
uint32_t user_config_loaded_ = 0;
|
||||
bool misconfigured_ = false;
|
||||
|
||||
@@ -36,6 +36,11 @@ bool SensorlessEstimator::update() {
|
||||
// TODO: we read values here which are modified by a higher priority interrupt.
|
||||
// This is not thread-safe.
|
||||
auto current_meas = axis_->motor_.current_meas_;
|
||||
if (!axis_->motor_.is_armed_) {
|
||||
// While the motor is disarmed the current is not measurable so we
|
||||
// assume that it's zero.
|
||||
current_meas = {0.0f, 0.0f};
|
||||
}
|
||||
if (!current_meas.has_value()) {
|
||||
error_ |= ERROR_UNKNOWN_CURRENT_MEASUREMENT;
|
||||
reset(); // Reset state for when the next valid current measurement comes in.
|
||||
|
||||
@@ -52,7 +52,11 @@ public:
|
||||
struct Config_t {
|
||||
float thermistor_poly_coeffs[num_coeffs_];
|
||||
|
||||
#if HW_VERSION_MAJOR == 3
|
||||
uint16_t gpio_pin = 4;
|
||||
#elif HW_VERSION_MAJOR == 4
|
||||
uint16_t gpio_pin = 2;
|
||||
#endif
|
||||
float temp_limit_lower = 100;
|
||||
float temp_limit_upper = 120;
|
||||
bool enabled = false;
|
||||
|
||||
Submodule Firmware/Private updated: 6abc10e94d...2bdcd0acc2
@@ -3,7 +3,7 @@
|
||||
#include <algorithm>
|
||||
#include <cstring>
|
||||
|
||||
#include "communication/can_helpers.hpp"
|
||||
#include "communication/can/can_helpers.hpp"
|
||||
|
||||
enum InputMode {
|
||||
INPUT_MODE_INACTIVE,
|
||||
|
||||
@@ -11,7 +11,7 @@
|
||||
|
||||
#include <doctest.h>
|
||||
|
||||
#include <communication/can_helpers.hpp>
|
||||
#include <communication/can/can_helpers.hpp>
|
||||
|
||||
using std::cout;
|
||||
using std::endl;
|
||||
|
||||
2
Firmware/ThirdParty/FreeRTOS/Source/tasks.c
vendored
2
Firmware/ThirdParty/FreeRTOS/Source/tasks.c
vendored
@@ -331,7 +331,7 @@ typedef tskTCB TCB_t;
|
||||
|
||||
/*lint -save -e956 A manual analysis and inspection has been used to determine
|
||||
which static variables must be declared volatile. */
|
||||
PRIVILEGED_DATA TCB_t * volatile pxCurrentTCB = NULL;
|
||||
__attribute__((used)) PRIVILEGED_DATA TCB_t * volatile pxCurrentTCB = NULL;
|
||||
|
||||
/* Lists for ready and blocked tasks. --------------------
|
||||
xDelayedTaskList1 and xDelayedTaskList2 could be move to function scople but
|
||||
|
||||
@@ -44,7 +44,7 @@ function compile(src_file, obj_file)
|
||||
tup.frule{
|
||||
inputs={src_file},
|
||||
extra_inputs = {'autogen/interfaces.hpp', 'autogen/function_stubs.hpp', 'autogen/endpoints.hpp', 'autogen/type_info.hpp'},
|
||||
command='^co^ '..compiler..' -c %f '..tostring(CFLAGS)..' -o %o',
|
||||
command='^o^ '..compiler..' -c %f '..tostring(CFLAGS)..' -o %o',
|
||||
outputs={obj_file}
|
||||
}
|
||||
end
|
||||
@@ -91,12 +91,12 @@ odrive_firmware_pkg = {
|
||||
'Drivers/STM32/stm32_gpio.cpp',
|
||||
'Drivers/STM32/stm32_nvm.c',
|
||||
'Drivers/STM32/stm32_spi_arbiter.cpp',
|
||||
'communication/can_simple.cpp',
|
||||
'communication/can/can_simple.cpp',
|
||||
'communication/can/odrive_can.cpp',
|
||||
'communication/communication.cpp',
|
||||
'communication/ascii_protocol.cpp',
|
||||
'communication/interface_uart.cpp',
|
||||
'communication/interface_usb.cpp',
|
||||
'communication/interface_can.cpp',
|
||||
'communication/interface_i2c.cpp',
|
||||
'FreeRTOS-openocd.c',
|
||||
'autogen/version.c'
|
||||
@@ -432,7 +432,7 @@ end
|
||||
|
||||
tup.frule{
|
||||
inputs=object_files,
|
||||
command='^c^ '..LINKER..' %f '..tostring(CFLAGS)..' '..tostring(LDFLAGS)..
|
||||
command='^o^ '..LINKER..' %f '..tostring(CFLAGS)..' '..tostring(LDFLAGS)..
|
||||
' -Wl,-Map=%O.map -o %o',
|
||||
outputs={'build/ODriveFirmware.elf', extra_outputs={'build/ODriveFirmware.map'}}
|
||||
}
|
||||
|
||||
@@ -3,6 +3,42 @@
|
||||
|
||||
#include <odrive_main.h>
|
||||
|
||||
bool CANSimple::init() {
|
||||
for (size_t i = 0; i < AXIS_COUNT; ++i) {
|
||||
if (!renew_subscription(i)) {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool CANSimple::renew_subscription(size_t i) {
|
||||
Axis& axis = axes[i];
|
||||
|
||||
// TODO: remove these two lines (see comment in header)
|
||||
node_ids_[i] = axis.config_.can.node_id;
|
||||
extended_node_ids_[i] = axis.config_.can.is_extended;
|
||||
|
||||
MsgIdFilterSpecs filter = {
|
||||
.id = {},
|
||||
.mask = (uint32_t)(0xffffffff << NUM_CMD_ID_BITS)
|
||||
};
|
||||
if (axis.config_.can.is_extended) {
|
||||
filter.id = (uint32_t)(axis.config_.can.node_id << NUM_CMD_ID_BITS);
|
||||
} else {
|
||||
filter.id = (uint16_t)(axis.config_.can.node_id << NUM_CMD_ID_BITS);
|
||||
}
|
||||
|
||||
if (subscription_handles_[i]) {
|
||||
canbus_->unsubscribe(subscription_handles_[i]);
|
||||
}
|
||||
|
||||
return canbus_->subscribe(filter, [](void* ctx, const can_Message_t& msg) {
|
||||
((CANSimple*)ctx)->handle_can_message(msg);
|
||||
}, this, &subscription_handles_[i]);
|
||||
}
|
||||
|
||||
void CANSimple::handle_can_message(const can_Message_t& msg) {
|
||||
// Frame
|
||||
// nodeID | CMD
|
||||
@@ -11,13 +47,13 @@ void CANSimple::handle_can_message(const can_Message_t& msg) {
|
||||
|
||||
for (auto& axis : axes) {
|
||||
if ((axis.config_.can.node_id == nodeID) && (axis.config_.can.is_extended == msg.isExt)) {
|
||||
doCommand(axis, msg);
|
||||
do_command(axis, msg);
|
||||
return;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void CANSimple::doCommand(Axis& axis, const can_Message_t& msg) {
|
||||
void CANSimple::do_command(Axis& axis, const can_Message_t& msg) {
|
||||
const uint32_t cmd = get_cmd_id(msg.id);
|
||||
axis.watchdog_feed();
|
||||
switch (cmd) {
|
||||
@@ -72,8 +108,8 @@ void CANSimple::doCommand(Axis& axis, const can_Message_t& msg) {
|
||||
case MSG_SET_CONTROLLER_MODES:
|
||||
set_controller_modes_callback(axis, msg);
|
||||
break;
|
||||
case MSG_SET_VEL_LIMIT:
|
||||
set_vel_limit_callback(axis, msg);
|
||||
case MSG_SET_LIMITS:
|
||||
set_limits_callback(axis, msg);
|
||||
break;
|
||||
case MSG_START_ANTICOGGING:
|
||||
start_anticogging_callback(axis, msg);
|
||||
@@ -118,7 +154,7 @@ void CANSimple::estop_callback(Axis& axis, const can_Message_t& msg) {
|
||||
axis.error_ |= Axis::ERROR_ESTOP_REQUESTED;
|
||||
}
|
||||
|
||||
int32_t CANSimple::get_motor_error_callback(const Axis& axis) {
|
||||
bool CANSimple::get_motor_error_callback(const Axis& axis) {
|
||||
can_Message_t txmsg;
|
||||
txmsg.id = axis.config_.can.node_id << NUM_CMD_ID_BITS;
|
||||
txmsg.id += MSG_GET_MOTOR_ERROR; // heartbeat ID
|
||||
@@ -127,10 +163,10 @@ int32_t CANSimple::get_motor_error_callback(const Axis& axis) {
|
||||
|
||||
can_setSignal(txmsg, axis.motor_.error_, 0, 32, true);
|
||||
|
||||
return odCAN->write(txmsg);
|
||||
return canbus_->send_message(txmsg);
|
||||
}
|
||||
|
||||
int32_t CANSimple::get_encoder_error_callback(const Axis& axis) {
|
||||
bool CANSimple::get_encoder_error_callback(const Axis& axis) {
|
||||
can_Message_t txmsg;
|
||||
txmsg.id = axis.config_.can.node_id << NUM_CMD_ID_BITS;
|
||||
txmsg.id += MSG_GET_ENCODER_ERROR; // heartbeat ID
|
||||
@@ -139,10 +175,10 @@ int32_t CANSimple::get_encoder_error_callback(const Axis& axis) {
|
||||
|
||||
can_setSignal(txmsg, axis.encoder_.error_, 0, 32, true);
|
||||
|
||||
return odCAN->write(txmsg);
|
||||
return canbus_->send_message(txmsg);
|
||||
}
|
||||
|
||||
int32_t CANSimple::get_sensorless_error_callback(const Axis& axis) {
|
||||
bool CANSimple::get_sensorless_error_callback(const Axis& axis) {
|
||||
can_Message_t txmsg;
|
||||
txmsg.id = axis.config_.can.node_id << NUM_CMD_ID_BITS;
|
||||
txmsg.id += MSG_GET_SENSORLESS_ERROR; // heartbeat ID
|
||||
@@ -151,7 +187,7 @@ int32_t CANSimple::get_sensorless_error_callback(const Axis& axis) {
|
||||
|
||||
can_setSignal(txmsg, axis.sensorless_estimator_.error_, 0, 32, true);
|
||||
|
||||
return odCAN->write(txmsg);
|
||||
return canbus_->send_message(txmsg);
|
||||
}
|
||||
|
||||
void CANSimple::set_axis_nodeid_callback(Axis& axis, const can_Message_t& msg) {
|
||||
@@ -166,7 +202,7 @@ void CANSimple::set_axis_startup_config_callback(Axis& axis, const can_Message_t
|
||||
// Not Implemented
|
||||
}
|
||||
|
||||
int32_t CANSimple::get_encoder_estimates_callback(const Axis& axis) {
|
||||
bool CANSimple::get_encoder_estimates_callback(const Axis& axis) {
|
||||
can_Message_t txmsg;
|
||||
txmsg.id = axis.config_.can.node_id << NUM_CMD_ID_BITS;
|
||||
txmsg.id += MSG_GET_ENCODER_ESTIMATES; // heartbeat ID
|
||||
@@ -176,10 +212,10 @@ int32_t CANSimple::get_encoder_estimates_callback(const Axis& axis) {
|
||||
can_setSignal<float>(txmsg, axis.encoder_.pos_estimate_.any().value_or(0.0f), 0, 32, true);
|
||||
can_setSignal<float>(txmsg, axis.encoder_.vel_estimate_.any().value_or(0.0f), 32, 32, true);
|
||||
|
||||
return odCAN->write(txmsg);
|
||||
return canbus_->send_message(txmsg);
|
||||
}
|
||||
|
||||
int32_t CANSimple::get_sensorless_estimates_callback(const Axis& axis) {
|
||||
bool CANSimple::get_sensorless_estimates_callback(const Axis& axis) {
|
||||
can_Message_t txmsg;
|
||||
txmsg.id = axis.config_.can.node_id << NUM_CMD_ID_BITS;
|
||||
txmsg.id += MSG_GET_SENSORLESS_ESTIMATES; // heartbeat ID
|
||||
@@ -191,10 +227,10 @@ int32_t CANSimple::get_sensorless_estimates_callback(const Axis& axis) {
|
||||
can_setSignal<float>(txmsg, axis.sensorless_estimator_.pll_pos_, 0, 32, true);
|
||||
can_setSignal<float>(txmsg, axis.sensorless_estimator_.vel_estimate_.any().value_or(0.0f), 32, 32, true);
|
||||
|
||||
return odCAN->write(txmsg);
|
||||
return canbus_->send_message(txmsg);
|
||||
}
|
||||
|
||||
int32_t CANSimple::get_encoder_count_callback(const Axis& axis) {
|
||||
bool CANSimple::get_encoder_count_callback(const Axis& axis) {
|
||||
can_Message_t txmsg;
|
||||
txmsg.id = axis.config_.can.node_id << NUM_CMD_ID_BITS;
|
||||
txmsg.id += MSG_GET_ENCODER_COUNT;
|
||||
@@ -203,7 +239,7 @@ int32_t CANSimple::get_encoder_count_callback(const Axis& axis) {
|
||||
|
||||
can_setSignal<int32_t>(txmsg, axis.encoder_.shadow_count_, 0, 32, true);
|
||||
can_setSignal<int32_t>(txmsg, axis.encoder_.count_in_cpr_, 32, 32, true);
|
||||
return odCAN->write(txmsg);
|
||||
return canbus_->send_message(txmsg);
|
||||
}
|
||||
|
||||
void CANSimple::set_input_pos_callback(Axis& axis, const can_Message_t& msg) {
|
||||
@@ -227,8 +263,9 @@ void CANSimple::set_controller_modes_callback(Axis& axis, const can_Message_t& m
|
||||
axis.controller_.config_.input_mode = static_cast<Controller::InputMode>(can_getSignal<int32_t>(msg, 32, 32, true));
|
||||
}
|
||||
|
||||
void CANSimple::set_vel_limit_callback(Axis& axis, const can_Message_t& msg) {
|
||||
void CANSimple::set_limits_callback(Axis& axis, const can_Message_t& msg) {
|
||||
axis.controller_.config_.vel_limit = can_getSignal<float>(msg, 0, 32, true);
|
||||
axis.motor_.config_.current_lim = can_getSignal<float>(msg, 32, 32, true);
|
||||
}
|
||||
|
||||
void CANSimple::start_anticogging_callback(const Axis& axis, const can_Message_t& msg) {
|
||||
@@ -252,7 +289,7 @@ void CANSimple::set_linear_count_callback(Axis& axis, const can_Message_t& msg){
|
||||
axis.encoder_.set_linear_count(can_getSignal<int32_t>(msg, 0, 32, true));
|
||||
}
|
||||
|
||||
int32_t CANSimple::get_iq_callback(const Axis& axis) {
|
||||
bool CANSimple::get_iq_callback(const Axis& axis) {
|
||||
can_Message_t txmsg;
|
||||
txmsg.id = axis.config_.can.node_id << NUM_CMD_ID_BITS;
|
||||
txmsg.id += MSG_GET_IQ;
|
||||
@@ -269,10 +306,10 @@ int32_t CANSimple::get_iq_callback(const Axis& axis) {
|
||||
can_setSignal<float>(txmsg, Idq_setpoint->first, 0, 32, true);
|
||||
can_setSignal<float>(txmsg, Idq_setpoint->second, 32, 32, true);
|
||||
|
||||
return odCAN->write(txmsg);
|
||||
return canbus_->send_message(txmsg);
|
||||
}
|
||||
|
||||
int32_t CANSimple::get_vbus_voltage_callback(const Axis& axis) {
|
||||
bool CANSimple::get_vbus_voltage_callback(const Axis& axis) {
|
||||
can_Message_t txmsg;
|
||||
|
||||
txmsg.id = axis.config_.can.node_id << NUM_CMD_ID_BITS;
|
||||
@@ -284,14 +321,54 @@ int32_t CANSimple::get_vbus_voltage_callback(const Axis& axis) {
|
||||
static_assert(sizeof(vbus_voltage) == sizeof(floatBytes));
|
||||
can_setSignal<float>(txmsg, vbus_voltage, 0, 32, true);
|
||||
|
||||
return odCAN->write(txmsg);
|
||||
return canbus_->send_message(txmsg);
|
||||
}
|
||||
|
||||
void CANSimple::clear_errors_callback(Axis& axis, const can_Message_t& msg) {
|
||||
odrv.clear_errors(); // TODO: might want to clear axis errors only
|
||||
}
|
||||
|
||||
int32_t CANSimple::send_heartbeat(const Axis& axis) {
|
||||
uint32_t CANSimple::service_stack() {
|
||||
uint32_t nextServiceTime = UINT32_MAX;
|
||||
uint32_t now = HAL_GetTick();
|
||||
|
||||
// TODO: remove this polling loop and replace with protocol hook
|
||||
for (size_t i = 0; i < AXIS_COUNT; ++i) {
|
||||
bool node_id_changed = (axes[i].config_.can.node_id != node_ids_[i])
|
||||
|| (axes[i].config_.can.is_extended != extended_node_ids_[i]);
|
||||
if (node_id_changed) {
|
||||
renew_subscription(i);
|
||||
}
|
||||
}
|
||||
|
||||
for (auto& a: axes) {
|
||||
MEASURE_TIME(a.task_times_.can_heartbeat) {
|
||||
if (a.config_.can.heartbeat_rate_ms > 0) {
|
||||
if ((now - a.can_.last_heartbeat) >= a.config_.can.heartbeat_rate_ms) {
|
||||
if (send_heartbeat(a))
|
||||
a.can_.last_heartbeat = now;
|
||||
}
|
||||
|
||||
int nextAxisService = a.can_.last_heartbeat + a.config_.can.heartbeat_rate_ms - now;
|
||||
nextServiceTime = std::min(nextServiceTime, static_cast<uint32_t>(std::max(0, nextAxisService)));
|
||||
}
|
||||
|
||||
if (a.config_.can.encoder_rate_ms > 0) {
|
||||
if ((now - a.can_.last_encoder) >= a.config_.can.encoder_rate_ms) {
|
||||
if (get_encoder_estimates_callback(a))
|
||||
a.can_.last_encoder = now;
|
||||
}
|
||||
|
||||
int nextAxisService = a.can_.last_encoder + a.config_.can.encoder_rate_ms - now;
|
||||
nextServiceTime = std::min(nextServiceTime, static_cast<uint32_t>(std::max(0, nextAxisService)));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return nextServiceTime;
|
||||
}
|
||||
|
||||
bool CANSimple::send_heartbeat(const Axis& axis) {
|
||||
can_Message_t txmsg;
|
||||
txmsg.id = axis.config_.can.node_id << NUM_CMD_ID_BITS;
|
||||
txmsg.id += MSG_ODRIVE_HEARTBEAT; // heartbeat ID
|
||||
@@ -301,23 +378,5 @@ int32_t CANSimple::send_heartbeat(const Axis& axis) {
|
||||
can_setSignal(txmsg, axis.error_, 0, 32, true);
|
||||
can_setSignal(txmsg, axis.current_state_, 32, 32, true);
|
||||
|
||||
return odCAN->write(txmsg);
|
||||
}
|
||||
|
||||
void CANSimple::send_cyclic(Axis& axis) {
|
||||
const uint32_t now = HAL_GetTick();
|
||||
|
||||
if (axis.config_.can.heartbeat_rate_ms > 0) {
|
||||
if ((now - axis.can_.last_heartbeat) >= axis.config_.can.heartbeat_rate_ms) {
|
||||
if(send_heartbeat(axis) >= 0)
|
||||
axis.can_.last_heartbeat = now;
|
||||
}
|
||||
}
|
||||
|
||||
if (axis.config_.can.encoder_rate_ms > 0) {
|
||||
if ((now - axis.can_.last_encoder) >= axis.config_.can.encoder_rate_ms) {
|
||||
if(get_encoder_estimates_callback(axis) >= 0)
|
||||
axis.can_.last_encoder = now;
|
||||
}
|
||||
}
|
||||
return canbus_->send_message(txmsg);
|
||||
}
|
||||
@@ -1,7 +1,8 @@
|
||||
#ifndef __CAN_SIMPLE_HPP_
|
||||
#define __CAN_SIMPLE_HPP_
|
||||
|
||||
#include "interface_can.hpp"
|
||||
#include "canbus.hpp"
|
||||
#include "axis.hpp"
|
||||
|
||||
class CANSimple {
|
||||
public:
|
||||
@@ -21,7 +22,7 @@ class CANSimple {
|
||||
MSG_SET_INPUT_POS,
|
||||
MSG_SET_INPUT_VEL,
|
||||
MSG_SET_INPUT_TORQUE,
|
||||
MSG_SET_VEL_LIMIT,
|
||||
MSG_SET_LIMITS,
|
||||
MSG_START_ANTICOGGING,
|
||||
MSG_SET_TRAJ_VEL_LIMIT,
|
||||
MSG_SET_TRAJ_ACCEL_LIMITS,
|
||||
@@ -34,24 +35,30 @@ class CANSimple {
|
||||
MSG_CO_HEARTBEAT_CMD = 0x700, // CANOpen NMT Heartbeat SEND
|
||||
};
|
||||
|
||||
static void handle_can_message(const can_Message_t& msg);
|
||||
static void doCommand(Axis& axis, const can_Message_t& cmd);
|
||||
CANSimple(CanBusBase* canbus) : canbus_(canbus) {}
|
||||
|
||||
// Cyclic Senders
|
||||
static int32_t send_heartbeat(const Axis& axis);
|
||||
static void send_cyclic(Axis& axis);
|
||||
bool init();
|
||||
uint32_t service_stack();
|
||||
|
||||
private:
|
||||
|
||||
bool renew_subscription(size_t i);
|
||||
bool send_heartbeat(const Axis& axis);
|
||||
|
||||
void handle_can_message(const can_Message_t& msg);
|
||||
|
||||
void do_command(Axis& axis, const can_Message_t& cmd);
|
||||
|
||||
// Get functions (msg.rtr bit must be set)
|
||||
static int32_t get_motor_error_callback(const Axis& axis);
|
||||
static int32_t get_encoder_error_callback(const Axis& axis);
|
||||
static int32_t get_controller_error_callback(const Axis& axis);
|
||||
static int32_t get_sensorless_error_callback(const Axis& axis);
|
||||
static int32_t get_encoder_estimates_callback(const Axis& axis);
|
||||
static int32_t get_encoder_count_callback(const Axis& axis);
|
||||
static int32_t get_iq_callback(const Axis& axis);
|
||||
static int32_t get_sensorless_estimates_callback(const Axis& axis);
|
||||
static int32_t get_vbus_voltage_callback(const Axis& axis);
|
||||
bool get_motor_error_callback(const Axis& axis);
|
||||
bool get_encoder_error_callback(const Axis& axis);
|
||||
bool get_controller_error_callback(const Axis& axis);
|
||||
bool get_sensorless_error_callback(const Axis& axis);
|
||||
bool get_encoder_estimates_callback(const Axis& axis);
|
||||
bool get_encoder_count_callback(const Axis& axis);
|
||||
bool get_iq_callback(const Axis& axis);
|
||||
bool get_sensorless_estimates_callback(const Axis& axis);
|
||||
bool get_vbus_voltage_callback(const Axis& axis);
|
||||
|
||||
// Set functions
|
||||
static void set_axis_nodeid_callback(Axis& axis, const can_Message_t& msg);
|
||||
@@ -61,7 +68,7 @@ class CANSimple {
|
||||
static void set_input_vel_callback(Axis& axis, const can_Message_t& msg);
|
||||
static void set_input_torque_callback(Axis& axis, const can_Message_t& msg);
|
||||
static void set_controller_modes_callback(Axis& axis, const can_Message_t& msg);
|
||||
static void set_vel_limit_callback(Axis& axis, const can_Message_t& msg);
|
||||
static void set_limits_callback(Axis& axis, const can_Message_t& msg);
|
||||
static void set_traj_vel_limit_callback(Axis& axis, const can_Message_t& msg);
|
||||
static void set_traj_accel_limits_callback(Axis& axis, const can_Message_t& msg);
|
||||
static void set_traj_inertia_callback(Axis& axis, const can_Message_t& msg);
|
||||
@@ -84,6 +91,14 @@ class CANSimple {
|
||||
static constexpr uint8_t get_cmd_id(uint32_t msgID) {
|
||||
return (msgID & 0x01F); // Bottom 5 bits
|
||||
}
|
||||
|
||||
CanBusBase* canbus_;
|
||||
CanBusBase::CanSubscription* subscription_handles_[AXIS_COUNT];
|
||||
|
||||
// TODO: we this is a hack but actually we should use protocol hooks to
|
||||
// renew our filter when the node ID changes
|
||||
uint32_t node_ids_[AXIS_COUNT];
|
||||
bool extended_node_ids_[AXIS_COUNT];
|
||||
};
|
||||
|
||||
#endif
|
||||
43
Firmware/communication/can/canbus.hpp
Normal file
43
Firmware/communication/can/canbus.hpp
Normal file
@@ -0,0 +1,43 @@
|
||||
#ifndef __CANBUS_HPP
|
||||
#define __CANBUS_HPP
|
||||
|
||||
#include "can_helpers.hpp"
|
||||
#include <variant>
|
||||
|
||||
struct MsgIdFilterSpecs {
|
||||
std::variant<uint16_t, uint32_t> id;
|
||||
uint32_t mask;
|
||||
};
|
||||
|
||||
class CanBusBase {
|
||||
public:
|
||||
typedef void(*on_can_message_cb_t)(void* ctx, const can_Message_t& message);
|
||||
struct CanSubscription {};
|
||||
|
||||
/**
|
||||
* @brief Sends the specified CAN message.
|
||||
*
|
||||
* @returns: true on success or false otherwise (e.g. if the send queue is
|
||||
* full).
|
||||
*/
|
||||
virtual bool send_message(const can_Message_t& message) = 0;
|
||||
|
||||
/**
|
||||
* @brief Registers a callback that will be invoked for every incoming CAN
|
||||
* message that matches the filter.
|
||||
*
|
||||
* @param handle: On success this handle is set to an opaque pointer that
|
||||
* can be used to cancel the subscription.
|
||||
*
|
||||
* @returns: true on success or false otherwise (e.g. if the maximum number
|
||||
* of subscriptions has been reached).
|
||||
*/
|
||||
virtual bool subscribe(const MsgIdFilterSpecs& filter, on_can_message_cb_t callback, void* ctx, CanSubscription** handle) = 0;
|
||||
|
||||
/**
|
||||
* @brief Deregisters a callback that was previously registered with subscribe().
|
||||
*/
|
||||
virtual bool unsubscribe(CanSubscription* handle) = 0;
|
||||
};
|
||||
|
||||
#endif // __CANBUS_HPP
|
||||
238
Firmware/communication/can/odrive_can.cpp
Normal file
238
Firmware/communication/can/odrive_can.cpp
Normal file
@@ -0,0 +1,238 @@
|
||||
#include "odrive_can.hpp"
|
||||
|
||||
#include <can.h>
|
||||
#include <cmsis_os.h>
|
||||
|
||||
#include "freertos_vars.h"
|
||||
#include "utils.hpp"
|
||||
|
||||
// Safer context handling via maps instead of arrays
|
||||
// #include <unordered_map>
|
||||
// std::unordered_map<CAN_HandleTypeDef *, ODriveCAN *> ctxMap;
|
||||
|
||||
|
||||
bool ODriveCAN::apply_config() {
|
||||
config_.parent = this;
|
||||
set_baud_rate(config_.baud_rate);
|
||||
return true;
|
||||
}
|
||||
|
||||
bool ODriveCAN::reinit() {
|
||||
HAL_CAN_Stop(handle_);
|
||||
HAL_CAN_ResetError(handle_);
|
||||
return (HAL_CAN_Init(handle_) == HAL_OK)
|
||||
&& (HAL_CAN_Start(handle_) == HAL_OK)
|
||||
&& (HAL_CAN_ActivateNotification(handle_, CAN_IT_RX_FIFO0_MSG_PENDING | CAN_IT_RX_FIFO1_MSG_PENDING | CAN_IT_TX_MAILBOX_EMPTY) == HAL_OK);
|
||||
}
|
||||
|
||||
bool ODriveCAN::start_server(CAN_HandleTypeDef* handle) {
|
||||
handle_ = handle;
|
||||
|
||||
handle_->Init.Prescaler = CAN_FREQ / config_.baud_rate;
|
||||
if (!reinit()) {
|
||||
return false;
|
||||
}
|
||||
|
||||
auto wrapper = [](void* ctx) {
|
||||
((ODriveCAN*)ctx)->can_server_thread();
|
||||
};
|
||||
osThreadDef(can_server_thread_def, wrapper, osPriorityNormal, 0, stack_size_ / sizeof(StackType_t));
|
||||
thread_id_ = osThreadCreate(osThread(can_server_thread_def), this);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void ODriveCAN::can_server_thread() {
|
||||
Protocol protocol = config_.protocol;
|
||||
|
||||
if (protocol & PROTOCOL_SIMPLE) {
|
||||
can_simple_.init();
|
||||
}
|
||||
|
||||
for (;;) {
|
||||
uint32_t status = HAL_CAN_GetError(handle_);
|
||||
if (status == HAL_CAN_ERROR_NONE) {
|
||||
uint32_t next_service_time = UINT32_MAX;
|
||||
|
||||
if (protocol & PROTOCOL_SIMPLE) {
|
||||
next_service_time = std::min(can_simple_.service_stack(), next_service_time);
|
||||
}
|
||||
|
||||
process_rx_fifo(CAN_RX_FIFO0);
|
||||
process_rx_fifo(CAN_RX_FIFO1);
|
||||
HAL_CAN_ActivateNotification(handle_, CAN_IT_RX_FIFO0_MSG_PENDING | CAN_IT_RX_FIFO1_MSG_PENDING | CAN_IT_TX_MAILBOX_EMPTY);
|
||||
|
||||
// wait at least 1ms to prevent busy-spin on failed sends
|
||||
osSemaphoreWait(sem_can, std::max(next_service_time, 1UL));
|
||||
} else if (status == HAL_CAN_ERROR_TIMEOUT) {
|
||||
HAL_CAN_ResetError(handle_);
|
||||
status = HAL_CAN_Start(handle_);
|
||||
if (status == HAL_OK)
|
||||
status = HAL_CAN_ActivateNotification(handle_, CAN_IT_RX_FIFO0_MSG_PENDING | CAN_IT_TX_MAILBOX_EMPTY);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Set one of only a few common baud rates. CAN doesn't do arbitrary baud rates well due to the time-quanta issue.
|
||||
// 21 TQ allows for easy sampling at exactly 80% (recommended by Vector Informatik GmbH for high reliability systems)
|
||||
// Conveniently, the CAN peripheral's 42MHz clock lets us easily create 21TQs for all common baud rates
|
||||
bool ODriveCAN::set_baud_rate(uint32_t baud_rate) {
|
||||
uint32_t prescaler = CAN_FREQ / baud_rate;
|
||||
if (prescaler * baud_rate == CAN_FREQ) {
|
||||
// valid baud rate
|
||||
config_.baud_rate = baud_rate;
|
||||
if (handle_) {
|
||||
handle_->Init.Prescaler = prescaler;
|
||||
return reinit();
|
||||
}
|
||||
return true;
|
||||
} else {
|
||||
// invalid baud rate - ignore
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
void ODriveCAN::process_rx_fifo(uint32_t fifo) {
|
||||
while (HAL_CAN_GetRxFifoFillLevel(handle_, fifo)) {
|
||||
CAN_RxHeaderTypeDef header;
|
||||
can_Message_t rxmsg;
|
||||
HAL_CAN_GetRxMessage(handle_, fifo, &header, rxmsg.buf);
|
||||
|
||||
rxmsg.isExt = header.IDE;
|
||||
rxmsg.id = rxmsg.isExt ? header.ExtId : header.StdId; // If it's an extended message, pass the extended ID
|
||||
rxmsg.len = header.DLC;
|
||||
rxmsg.rtr = header.RTR;
|
||||
|
||||
// TODO: this could be optimized with an ahead-of-time computed
|
||||
// index-to-filter map
|
||||
|
||||
size_t fifo0_idx = 0;
|
||||
size_t fifo1_idx = 0;
|
||||
|
||||
// Find the triggered subscription item based on header.FilterMatchIndex
|
||||
auto it = std::find_if(subscriptions_.begin(), subscriptions_.end(), [&](auto& s) {
|
||||
size_t current_idx = (s.fifo == 0 ? fifo0_idx : fifo1_idx)++;
|
||||
return (header.FilterMatchIndex == current_idx) && (s.fifo == fifo);
|
||||
});
|
||||
|
||||
if (it == subscriptions_.end()) {
|
||||
continue;
|
||||
}
|
||||
|
||||
it->callback(it->ctx, rxmsg);
|
||||
}
|
||||
}
|
||||
|
||||
// Send a CAN message on the bus
|
||||
bool ODriveCAN::send_message(const can_Message_t &txmsg) {
|
||||
if (HAL_CAN_GetError(handle_) != HAL_CAN_ERROR_NONE) {
|
||||
return false;
|
||||
}
|
||||
|
||||
CAN_TxHeaderTypeDef header;
|
||||
header.StdId = txmsg.id;
|
||||
header.ExtId = txmsg.id;
|
||||
header.IDE = txmsg.isExt ? CAN_ID_EXT : CAN_ID_STD;
|
||||
header.RTR = CAN_RTR_DATA;
|
||||
header.DLC = txmsg.len;
|
||||
header.TransmitGlobalTime = FunctionalState::DISABLE;
|
||||
|
||||
uint32_t retTxMailbox = 0;
|
||||
if (!HAL_CAN_GetTxMailboxesFreeLevel(handle_)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
return HAL_CAN_AddTxMessage(handle_, &header, (uint8_t*)txmsg.buf, &retTxMailbox) == HAL_OK;
|
||||
}
|
||||
|
||||
//void ODriveCAN::set_error(Error error) {
|
||||
// error_ |= error;
|
||||
//}
|
||||
|
||||
bool ODriveCAN::subscribe(const MsgIdFilterSpecs& filter, on_can_message_cb_t callback, void* ctx, CanSubscription** handle) {
|
||||
auto it = std::find_if(subscriptions_.begin(), subscriptions_.end(), [](auto& subscription) {
|
||||
return subscription.fifo == kCanFifoNone;
|
||||
});
|
||||
|
||||
if (it == subscriptions_.end()) {
|
||||
return false; // all subscription slots in use
|
||||
}
|
||||
|
||||
it->callback = callback;
|
||||
it->ctx = ctx;
|
||||
it->fifo = CAN_RX_FIFO0; // TODO: make customizable
|
||||
if (handle) {
|
||||
*handle = &*it;
|
||||
}
|
||||
|
||||
bool is_extended = filter.id.index() == 1;
|
||||
uint32_t id = is_extended ?
|
||||
((std::get<1>(filter.id) << 3) | (1 << 2)) :
|
||||
(std::get<0>(filter.id) << 21);
|
||||
uint32_t mask = (is_extended ? (filter.mask << 3) : (filter.mask << 21))
|
||||
| (1 << 2); // care about the is_extended bit
|
||||
|
||||
CAN_FilterTypeDef hal_filter;
|
||||
hal_filter.FilterActivation = ENABLE;
|
||||
hal_filter.FilterBank = &*it - &subscriptions_[0];
|
||||
hal_filter.FilterFIFOAssignment = it->fifo;
|
||||
hal_filter.FilterIdHigh = (id >> 16) & 0xffff;
|
||||
hal_filter.FilterIdLow = id & 0xffff;
|
||||
hal_filter.FilterMaskIdHigh = (mask >> 16) & 0xffff;
|
||||
hal_filter.FilterMaskIdLow = mask & 0xffff;
|
||||
hal_filter.FilterMode = CAN_FILTERMODE_IDMASK;
|
||||
hal_filter.FilterScale = CAN_FILTERSCALE_32BIT;
|
||||
|
||||
if (HAL_CAN_ConfigFilter(handle_, &hal_filter) != HAL_OK) {
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
bool ODriveCAN::unsubscribe(CanSubscription* handle) {
|
||||
ODriveCanSubscription* subscription = static_cast<ODriveCanSubscription*>(handle);
|
||||
if (subscription < subscriptions_.begin() || subscription >= subscriptions_.end()) {
|
||||
return false;
|
||||
}
|
||||
if (subscription->fifo != kCanFifoNone) {
|
||||
return false; // not in use
|
||||
}
|
||||
|
||||
subscription->fifo = kCanFifoNone;
|
||||
|
||||
CAN_FilterTypeDef hal_filter = {};
|
||||
hal_filter.FilterActivation = DISABLE;
|
||||
return HAL_CAN_ConfigFilter(handle_, &hal_filter) == HAL_OK;
|
||||
}
|
||||
|
||||
void HAL_CAN_TxMailbox0CompleteCallback(CAN_HandleTypeDef *hcan) {
|
||||
HAL_CAN_DeactivateNotification(hcan, CAN_IT_TX_MAILBOX_EMPTY);
|
||||
osSemaphoreRelease(sem_can);
|
||||
}
|
||||
void HAL_CAN_TxMailbox1CompleteCallback(CAN_HandleTypeDef *hcan) {
|
||||
HAL_CAN_DeactivateNotification(hcan, CAN_IT_TX_MAILBOX_EMPTY);
|
||||
osSemaphoreRelease(sem_can);
|
||||
}
|
||||
void HAL_CAN_TxMailbox2CompleteCallback(CAN_HandleTypeDef *hcan) {
|
||||
HAL_CAN_DeactivateNotification(hcan, CAN_IT_TX_MAILBOX_EMPTY);
|
||||
osSemaphoreRelease(sem_can);
|
||||
}
|
||||
void HAL_CAN_TxMailbox0AbortCallback(CAN_HandleTypeDef *hcan) {}
|
||||
void HAL_CAN_TxMailbox1AbortCallback(CAN_HandleTypeDef *hcan) {}
|
||||
void HAL_CAN_TxMailbox2AbortCallback(CAN_HandleTypeDef *hcan) {}
|
||||
void HAL_CAN_RxFifo0MsgPendingCallback(CAN_HandleTypeDef *hcan) {
|
||||
HAL_CAN_DeactivateNotification(hcan, CAN_IT_RX_FIFO0_MSG_PENDING);
|
||||
osSemaphoreRelease(sem_can);
|
||||
}
|
||||
void HAL_CAN_RxFifo0FullCallback(CAN_HandleTypeDef *hcan) {
|
||||
HAL_CAN_DeactivateNotification(hcan, CAN_IT_RX_FIFO1_MSG_PENDING);
|
||||
osSemaphoreRelease(sem_can);
|
||||
}
|
||||
void HAL_CAN_RxFifo1MsgPendingCallback(CAN_HandleTypeDef *hcan) {}
|
||||
void HAL_CAN_RxFifo1FullCallback(CAN_HandleTypeDef *hcan) {}
|
||||
void HAL_CAN_SleepCallback(CAN_HandleTypeDef *hcan) {}
|
||||
void HAL_CAN_WakeUpFromRxMsgCallback(CAN_HandleTypeDef *hcan) {}
|
||||
|
||||
void HAL_CAN_ErrorCallback(CAN_HandleTypeDef *hcan) {
|
||||
//HAL_CAN_ResetError(hcan);
|
||||
}
|
||||
68
Firmware/communication/can/odrive_can.hpp
Normal file
68
Firmware/communication/can/odrive_can.hpp
Normal file
@@ -0,0 +1,68 @@
|
||||
#ifndef __ODRIVE_CAN_HPP
|
||||
#define __ODRIVE_CAN_HPP
|
||||
|
||||
#include <cmsis_os.h>
|
||||
|
||||
#include "canbus.hpp"
|
||||
#include "can_simple.hpp"
|
||||
#include <autogen/interfaces.hpp>
|
||||
|
||||
#define CAN_CLK_HZ (42000000)
|
||||
#define CAN_CLK_MHZ (42)
|
||||
|
||||
// Anonymous enum for defining the most common CAN baud rates
|
||||
enum {
|
||||
CAN_BAUD_125K = 125000,
|
||||
CAN_BAUD_250K = 250000,
|
||||
CAN_BAUD_500K = 500000,
|
||||
CAN_BAUD_1000K = 1000000,
|
||||
CAN_BAUD_1M = 1000000
|
||||
};
|
||||
|
||||
class ODriveCAN : public CanBusBase, public ODriveIntf::CanIntf {
|
||||
public:
|
||||
struct Config_t {
|
||||
uint32_t baud_rate = CAN_BAUD_250K;
|
||||
Protocol protocol = PROTOCOL_SIMPLE;
|
||||
|
||||
ODriveCAN* parent = nullptr; // set in apply_config()
|
||||
void set_baud_rate(uint32_t value) { parent->set_baud_rate(baud_rate); }
|
||||
};
|
||||
|
||||
ODriveCAN() {}
|
||||
|
||||
bool apply_config();
|
||||
bool start_server(CAN_HandleTypeDef* handle);
|
||||
|
||||
Error error_ = ERROR_NONE;
|
||||
|
||||
Config_t config_;
|
||||
CANSimple can_simple_{this};
|
||||
|
||||
osThreadId thread_id_;
|
||||
const uint32_t stack_size_ = 1024; // Bytes
|
||||
|
||||
private:
|
||||
static const uint8_t kCanFifoNone = 0xff;
|
||||
|
||||
struct ODriveCanSubscription : CanSubscription {
|
||||
uint8_t fifo = kCanFifoNone;
|
||||
on_can_message_cb_t callback;
|
||||
void* ctx;
|
||||
};
|
||||
|
||||
bool reinit();
|
||||
void can_server_thread();
|
||||
bool set_baud_rate(uint32_t baud_rate);
|
||||
void process_rx_fifo(uint32_t fifo);
|
||||
bool send_message(const can_Message_t& message) final;
|
||||
bool subscribe(const MsgIdFilterSpecs& filter, on_can_message_cb_t callback, void* ctx, CanSubscription** handle) final;
|
||||
bool unsubscribe(CanSubscription* handle) final;
|
||||
|
||||
// Hardware supports at most 28 filters unless we do optimizations. For now
|
||||
// we don't need that many.
|
||||
std::array<ODriveCanSubscription, 8> subscriptions_;
|
||||
CAN_HandleTypeDef *handle_ = nullptr;
|
||||
};
|
||||
|
||||
#endif // __ODRIVE_CAN_HPP
|
||||
@@ -56,7 +56,7 @@ void init_communication(void) {
|
||||
}
|
||||
|
||||
if (odrv.config_.enable_can_a) {
|
||||
odCAN->start_can_server();
|
||||
odrv.can_.start_server(&hcan1);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -1,218 +0,0 @@
|
||||
#include "interface_can.hpp"
|
||||
|
||||
#include <fibre/../../crc.hpp>
|
||||
#include "freertos_vars.h"
|
||||
#include "utils.hpp"
|
||||
|
||||
#include <can.h>
|
||||
#include <cmsis_os.h>
|
||||
|
||||
// Specific CAN Protocols
|
||||
#include "can_simple.hpp"
|
||||
|
||||
// Safer context handling via maps instead of arrays
|
||||
// #include <unordered_map>
|
||||
// std::unordered_map<CAN_HandleTypeDef *, ODriveCAN *> ctxMap;
|
||||
|
||||
// Constructor is called by communication.cpp and the handle is assigned appropriately
|
||||
ODriveCAN::ODriveCAN(ODriveCAN::Config_t &config, CAN_HandleTypeDef *handle)
|
||||
: config_{config},
|
||||
handle_{handle} {
|
||||
// ctxMap[handle_] = this;
|
||||
}
|
||||
|
||||
void ODriveCAN::can_server_thread() {
|
||||
for (;;) {
|
||||
uint32_t status = HAL_CAN_GetError(handle_);
|
||||
if (status == HAL_CAN_ERROR_NONE) {
|
||||
can_Message_t rxmsg;
|
||||
|
||||
osSemaphoreWait(sem_can, 10); // Poll every 10ms regardless of sempahore status
|
||||
while (available()) {
|
||||
read(rxmsg);
|
||||
switch (config_.protocol) {
|
||||
case PROTOCOL_SIMPLE:
|
||||
CANSimple::handle_can_message(rxmsg);
|
||||
break;
|
||||
}
|
||||
}
|
||||
HAL_CAN_ActivateNotification(handle_, CAN_IT_RX_FIFO0_MSG_PENDING | CAN_IT_TX_MAILBOX_EMPTY);
|
||||
} else {
|
||||
if (status == HAL_CAN_ERROR_TIMEOUT) {
|
||||
HAL_CAN_ResetError(handle_);
|
||||
status = HAL_CAN_Start(handle_);
|
||||
if (status == HAL_OK)
|
||||
status = HAL_CAN_ActivateNotification(handle_, CAN_IT_RX_FIFO0_MSG_PENDING | CAN_IT_TX_MAILBOX_EMPTY);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static void can_server_thread_wrapper(void *ctx) {
|
||||
reinterpret_cast<ODriveCAN *>(ctx)->can_server_thread();
|
||||
reinterpret_cast<ODriveCAN *>(ctx)->thread_id_valid_ = false;
|
||||
}
|
||||
|
||||
bool ODriveCAN::start_can_server() {
|
||||
HAL_StatusTypeDef status;
|
||||
|
||||
set_baud_rate(config_.baud_rate);
|
||||
|
||||
status = HAL_CAN_Init(handle_);
|
||||
|
||||
CAN_FilterTypeDef filter;
|
||||
filter.FilterActivation = ENABLE;
|
||||
filter.FilterBank = 0;
|
||||
filter.FilterFIFOAssignment = CAN_RX_FIFO0;
|
||||
filter.FilterIdHigh = 0x0000;
|
||||
filter.FilterIdLow = 0x0000;
|
||||
filter.FilterMaskIdHigh = 0x0000;
|
||||
filter.FilterMaskIdLow = 0x0000;
|
||||
filter.FilterMode = CAN_FILTERMODE_IDMASK;
|
||||
filter.FilterScale = CAN_FILTERSCALE_32BIT;
|
||||
|
||||
status = HAL_CAN_ConfigFilter(handle_, &filter);
|
||||
|
||||
status = HAL_CAN_Start(handle_);
|
||||
if (status == HAL_OK)
|
||||
status = HAL_CAN_ActivateNotification(handle_, CAN_IT_RX_FIFO0_MSG_PENDING | CAN_IT_TX_MAILBOX_EMPTY);
|
||||
|
||||
osThreadDef(can_server_thread_def, can_server_thread_wrapper, osPriorityNormal, 0, stack_size_ / sizeof(StackType_t));
|
||||
thread_id_ = osThreadCreate(osThread(can_server_thread_def), this);
|
||||
thread_id_valid_ = true;
|
||||
|
||||
return status;
|
||||
}
|
||||
|
||||
// Send a CAN message on the bus
|
||||
int32_t ODriveCAN::write(can_Message_t &txmsg) {
|
||||
if (HAL_CAN_GetError(handle_) == HAL_CAN_ERROR_NONE) {
|
||||
CAN_TxHeaderTypeDef header;
|
||||
header.StdId = txmsg.id;
|
||||
header.ExtId = txmsg.id;
|
||||
header.IDE = txmsg.isExt ? CAN_ID_EXT : CAN_ID_STD;
|
||||
header.RTR = CAN_RTR_DATA;
|
||||
header.DLC = txmsg.len;
|
||||
header.TransmitGlobalTime = FunctionalState::DISABLE;
|
||||
|
||||
uint32_t retTxMailbox = 0;
|
||||
if (HAL_CAN_GetTxMailboxesFreeLevel(handle_) > 0)
|
||||
HAL_CAN_AddTxMessage(handle_, &header, txmsg.buf, &retTxMailbox);
|
||||
else
|
||||
return -1;
|
||||
return (int32_t)retTxMailbox;
|
||||
} else {
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
|
||||
uint32_t ODriveCAN::available() {
|
||||
return (HAL_CAN_GetRxFifoFillLevel(handle_, CAN_RX_FIFO0) + HAL_CAN_GetRxFifoFillLevel(handle_, CAN_RX_FIFO1));
|
||||
}
|
||||
|
||||
bool ODriveCAN::read(can_Message_t &rxmsg) {
|
||||
CAN_RxHeaderTypeDef header;
|
||||
bool validRead = false;
|
||||
if (HAL_CAN_GetRxFifoFillLevel(handle_, CAN_RX_FIFO0) > 0) {
|
||||
HAL_CAN_GetRxMessage(handle_, CAN_RX_FIFO0, &header, rxmsg.buf);
|
||||
validRead = true;
|
||||
} else if (HAL_CAN_GetRxFifoFillLevel(handle_, CAN_RX_FIFO1) > 0) {
|
||||
HAL_CAN_GetRxMessage(handle_, CAN_RX_FIFO1, &header, rxmsg.buf);
|
||||
validRead = true;
|
||||
}
|
||||
|
||||
rxmsg.isExt = header.IDE;
|
||||
rxmsg.id = rxmsg.isExt ? header.ExtId : header.StdId; // If it's an extended message, pass the extended ID
|
||||
rxmsg.len = header.DLC;
|
||||
rxmsg.rtr = header.RTR;
|
||||
|
||||
return validRead;
|
||||
}
|
||||
|
||||
// Set one of only a few common baud rates. CAN doesn't do arbitrary baud rates well due to the time-quanta issue.
|
||||
// 21 TQ allows for easy sampling at exactly 80% (recommended by Vector Informatik GmbH for high reliability systems)
|
||||
// Conveniently, the CAN peripheral's 42MHz clock lets us easily create 21TQs for all common baud rates
|
||||
void ODriveCAN::set_baud_rate(uint32_t baudRate) {
|
||||
switch (baudRate) {
|
||||
case CAN_BAUD_125K:
|
||||
handle_->Init.Prescaler = CAN_FREQ / 125000UL;
|
||||
config_.baud_rate = baudRate;
|
||||
reinit_can();
|
||||
break;
|
||||
|
||||
case CAN_BAUD_250K:
|
||||
handle_->Init.Prescaler = CAN_FREQ / 250000UL;
|
||||
config_.baud_rate = baudRate;
|
||||
reinit_can();
|
||||
break;
|
||||
|
||||
case CAN_BAUD_500K:
|
||||
handle_->Init.Prescaler = CAN_FREQ / 500000UL;
|
||||
config_.baud_rate = baudRate;
|
||||
reinit_can();
|
||||
break;
|
||||
|
||||
case CAN_BAUD_1000K:
|
||||
handle_->Init.Prescaler = CAN_FREQ / 1000000UL;
|
||||
config_.baud_rate = baudRate;
|
||||
reinit_can();
|
||||
break;
|
||||
|
||||
default:
|
||||
// baudRate is invalid, so don't accept it.
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void ODriveCAN::reinit_can() {
|
||||
HAL_CAN_Stop(handle_);
|
||||
HAL_CAN_Init(handle_);
|
||||
auto status = HAL_CAN_Start(handle_);
|
||||
if (status == HAL_OK)
|
||||
status = HAL_CAN_ActivateNotification(handle_, CAN_IT_RX_FIFO0_MSG_PENDING | CAN_IT_TX_MAILBOX_EMPTY);
|
||||
}
|
||||
|
||||
void ODriveCAN::set_error(Error error) {
|
||||
error_ |= error;
|
||||
}
|
||||
|
||||
// This function is called by each axis.
|
||||
// It provides an abstraction from the specific CAN protocol in use
|
||||
void ODriveCAN::send_cyclic(Axis &axis) {
|
||||
// Handle heartbeat message
|
||||
switch (config_.protocol) {
|
||||
case PROTOCOL_SIMPLE:
|
||||
CANSimple::send_cyclic(axis);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void HAL_CAN_TxMailbox0CompleteCallback(CAN_HandleTypeDef *hcan) {
|
||||
HAL_CAN_DeactivateNotification(hcan, CAN_IT_TX_MAILBOX_EMPTY);
|
||||
osSemaphoreRelease(sem_can);
|
||||
}
|
||||
void HAL_CAN_TxMailbox1CompleteCallback(CAN_HandleTypeDef *hcan) {
|
||||
HAL_CAN_DeactivateNotification(hcan, CAN_IT_TX_MAILBOX_EMPTY);
|
||||
osSemaphoreRelease(sem_can);
|
||||
}
|
||||
void HAL_CAN_TxMailbox2CompleteCallback(CAN_HandleTypeDef *hcan) {
|
||||
HAL_CAN_DeactivateNotification(hcan, CAN_IT_TX_MAILBOX_EMPTY);
|
||||
osSemaphoreRelease(sem_can);
|
||||
}
|
||||
void HAL_CAN_TxMailbox0AbortCallback(CAN_HandleTypeDef *hcan) {}
|
||||
void HAL_CAN_TxMailbox1AbortCallback(CAN_HandleTypeDef *hcan) {}
|
||||
void HAL_CAN_TxMailbox2AbortCallback(CAN_HandleTypeDef *hcan) {}
|
||||
void HAL_CAN_RxFifo0MsgPendingCallback(CAN_HandleTypeDef *hcan) {
|
||||
HAL_CAN_DeactivateNotification(hcan, CAN_IT_RX_FIFO0_MSG_PENDING);
|
||||
osSemaphoreRelease(sem_can);
|
||||
}
|
||||
void HAL_CAN_RxFifo0FullCallback(CAN_HandleTypeDef *hcan) {
|
||||
// osSemaphoreRelease(sem_can);
|
||||
}
|
||||
void HAL_CAN_RxFifo1MsgPendingCallback(CAN_HandleTypeDef *hcan) {}
|
||||
void HAL_CAN_RxFifo1FullCallback(CAN_HandleTypeDef *hcan) {}
|
||||
void HAL_CAN_SleepCallback(CAN_HandleTypeDef *hcan) {}
|
||||
void HAL_CAN_WakeUpFromRxMsgCallback(CAN_HandleTypeDef *hcan) {}
|
||||
void HAL_CAN_ErrorCallback(CAN_HandleTypeDef *hcan) {
|
||||
HAL_CAN_ResetError(hcan);
|
||||
}
|
||||
@@ -1,55 +1,10 @@
|
||||
#ifndef __INTERFACE_CAN_HPP
|
||||
#define __INTERFACE_CAN_HPP
|
||||
|
||||
#include <cmsis_os.h>
|
||||
#include "odrive_main.h"
|
||||
#include "can_helpers.hpp"
|
||||
//#include <cmsis_os.h>
|
||||
//#include "odrive_main.h"
|
||||
//#include "can_helpers.hpp"
|
||||
//#include <communication/can/can_simple.hpp>
|
||||
//// Other protocol implementations here
|
||||
|
||||
#define CAN_CLK_HZ (42000000)
|
||||
#define CAN_CLK_MHZ (42)
|
||||
|
||||
// Anonymous enum for defining the most common CAN baud rates
|
||||
enum {
|
||||
CAN_BAUD_125K = 125000,
|
||||
CAN_BAUD_250K = 250000,
|
||||
CAN_BAUD_500K = 500000,
|
||||
CAN_BAUD_1000K = 1000000,
|
||||
CAN_BAUD_1M = 1000000
|
||||
};
|
||||
|
||||
class ODriveCAN : public ODriveIntf::CanIntf {
|
||||
public:
|
||||
struct Config_t {
|
||||
uint32_t baud_rate = CAN_BAUD_250K;
|
||||
Protocol protocol = PROTOCOL_SIMPLE;
|
||||
};
|
||||
|
||||
ODriveCAN(ODriveCAN::Config_t &config, CAN_HandleTypeDef *handle);
|
||||
|
||||
// Thread Relevant Data
|
||||
osThreadId thread_id_;
|
||||
const uint32_t stack_size_ = 1024; // Bytes
|
||||
Error error_ = ERROR_NONE;
|
||||
|
||||
volatile bool thread_id_valid_ = false;
|
||||
bool start_can_server();
|
||||
void can_server_thread();
|
||||
void send_cyclic(Axis& axis);
|
||||
void reinit_can();
|
||||
|
||||
void set_error(Error error);
|
||||
|
||||
// I/O Functions
|
||||
uint32_t available();
|
||||
int32_t write(can_Message_t &txmsg);
|
||||
bool read(can_Message_t &rxmsg);
|
||||
|
||||
ODriveCAN::Config_t &config_;
|
||||
|
||||
private:
|
||||
CAN_HandleTypeDef *handle_ = nullptr;
|
||||
|
||||
void set_baud_rate(uint32_t baudRate);
|
||||
};
|
||||
|
||||
#endif // __INTERFACE_CAN_HPP
|
||||
#endif
|
||||
|
||||
@@ -92,11 +92,12 @@ template<> struct Codec<float> {
|
||||
};
|
||||
template<typename T>
|
||||
struct Codec<T, std::enable_if_t<std::is_enum<T>::value>> {
|
||||
using int_type = std::underlying_type_t<T>;
|
||||
static std::optional<T> decode(cbufptr_t* buffer) {
|
||||
std::optional<int32_t> int_val = SimpleSerializer<int32_t, false>::read(&(buffer->begin()), buffer->end());
|
||||
std::optional<int_type> int_val = SimpleSerializer<int_type, false>::read(&(buffer->begin()), buffer->end());
|
||||
return int_val.has_value() ? std::make_optional(static_cast<T>(*int_val)) : std::nullopt;
|
||||
}
|
||||
static bool encode(T value, bufptr_t* buffer) { return SimpleSerializer<int32_t, false>::write(value, &(buffer->begin()), buffer->end()); }
|
||||
static bool encode(T value, bufptr_t* buffer) { return SimpleSerializer<int_type, false>::write(value, &(buffer->begin()), buffer->end()); }
|
||||
};
|
||||
template<> struct Codec<endpoint_ref_t> {
|
||||
static std::optional<endpoint_ref_t> decode(cbufptr_t* buffer) {
|
||||
|
||||
@@ -179,7 +179,7 @@ interfaces:
|
||||
Example: `step_gpio_pin` of both axes were set to the same GPIO.
|
||||
|
||||
oscilloscope: {type: Oscilloscope}
|
||||
can: {type: Can, c_name: get_can()}
|
||||
can: {type: Can}
|
||||
test_property: uint32
|
||||
|
||||
functions:
|
||||
@@ -381,10 +381,8 @@ interfaces:
|
||||
config:
|
||||
c_is_class: False
|
||||
attributes:
|
||||
baud_rate: readonly uint32
|
||||
baud_rate: {type: uint32, c_setter: 'set_baud_rate'}
|
||||
protocol: Protocol
|
||||
functions:
|
||||
set_baud_rate: {in: {baudRate: uint32}}
|
||||
|
||||
ODrive.Endpoint:
|
||||
c_is_class: False
|
||||
@@ -420,7 +418,6 @@ interfaces:
|
||||
last_drv_fault: readonly uint32
|
||||
current_state: readonly AxisState
|
||||
requested_state: AxisState
|
||||
loop_counter: readonly uint32
|
||||
is_homed: {type: bool, c_name: homing_.is_homed}
|
||||
config:
|
||||
c_is_class: False
|
||||
@@ -672,6 +669,7 @@ interfaces:
|
||||
UNKNOWN_VOLTAGE_COMMAND: {doc: The current controller did not get a valid feedforward voltage setpoint.}
|
||||
UNKNOWN_GAINS: {doc: The current controller gains were not configured. Run motor calibration or set `config.phase_resistance` and `config.phase_inductance` manually.}
|
||||
CONTROLLER_INITIALIZING: {doc: Internal value used while the controller is not yet ready to generate PWM timings.}
|
||||
UNBALANCED_PHASES: {doc: The motor pahses are not balanced.}
|
||||
is_armed: readonly bool
|
||||
is_calibrated: readonly bool
|
||||
current_meas_phA: {type: readonly float32, c_getter: 'current_meas_.value_or(Iph_ABC_t{0.0f, 0.0f, 0.0f}).phA'}
|
||||
@@ -1114,6 +1112,7 @@ interfaces:
|
||||
implements: ODrive.Config
|
||||
attributes:
|
||||
# TODO: add support for arrays
|
||||
gpio0_mode: {type: ODrive.GpioMode, doc: Mode of GPIO0 (changes take effect after reboot), c_name: 'gpio_modes[0]'}
|
||||
gpio1_mode: {type: ODrive.GpioMode, doc: Mode of GPIO1 (changes take effect after reboot), c_name: 'gpio_modes[1]'}
|
||||
gpio2_mode: {type: ODrive.GpioMode, doc: Mode of GPIO2 (changes take effect after reboot), c_name: 'gpio_modes[2]'}
|
||||
gpio3_mode: {type: ODrive.GpioMode, doc: Mode of GPIO3 (changes take effect after reboot), c_name: 'gpio_modes[3]'}
|
||||
@@ -1191,7 +1190,7 @@ valuetypes:
|
||||
AsciiAndStdout: {doc: Combination of `Ascii` and `Stdout`.}
|
||||
|
||||
ODrive.Can.Protocol:
|
||||
values: {SIMPLE: }
|
||||
flags: {SIMPLE: }
|
||||
|
||||
ODrive.Axis.AxisState: # TODO: remove redundant "Axis" in name
|
||||
values:
|
||||
|
||||
@@ -3,7 +3,7 @@
|
||||
#CONFIG_BOARD_VERSION=v3.5-24V
|
||||
CONFIG_DEBUG=false
|
||||
CONFIG_DOCTEST=false
|
||||
CONFIG_USE_LTO=true
|
||||
CONFIG_USE_LTO=false
|
||||
|
||||
# Uncomment this to error on compilation warnings
|
||||
#CONFIG_STRICT=true
|
||||
|
||||
@@ -38,5 +38,19 @@ npm run electron:serve
|
||||
npm run electron:build
|
||||
```
|
||||
|
||||
### Build electron app for all platforms
|
||||
```
|
||||
npm run electron:build -- -mwl
|
||||
```
|
||||
|
||||
### Building for rpi and potentially other ARM platform devices
|
||||
|
||||
PhantomJS is required as a dependency, so it must be installed first:
|
||||
```
|
||||
sudo apt install phantomjs
|
||||
```
|
||||
|
||||
After it is installed, `npm run electron:build` can be used to build the AppImage for ARM
|
||||
|
||||
### Customize configuration
|
||||
See [Configuration Reference](https://cli.vuejs.org/config/).
|
||||
|
||||
413
GUI/package-lock.json
generated
413
GUI/package-lock.json
generated
File diff suppressed because it is too large
Load Diff
@@ -6,7 +6,10 @@
|
||||
"serve": "vue-cli-service serve",
|
||||
"build": "vue-cli-service build",
|
||||
"lint": "vue-cli-service lint",
|
||||
"electron:build": "electron-icon-builder --input=./public/icon.png --output=build --flatten && vue-cli-service electron:build",
|
||||
"enumGenerate": "node scripts/enumGenerate.js",
|
||||
"preelectron:build": "electron-icon-builder --input=./public/icon.png --output=build --flatten && npm run enumGenerate",
|
||||
"electron:build": "vue-cli-service electron:build",
|
||||
"preelectron:serve": "npm run enumGenerate",
|
||||
"electron:serve": "vue-cli-service electron:serve",
|
||||
"postinstall": "electron-builder install-app-deps",
|
||||
"postuninstall": "electron-builder install-app-deps",
|
||||
@@ -19,8 +22,7 @@
|
||||
"core-js": "^3.6.5",
|
||||
"electron": "^9.1.1",
|
||||
"file-saver": "^2.0.2",
|
||||
"socket.io": "^2.3.0",
|
||||
"socket.io-client": "^2.3.0",
|
||||
"socket.io-client": "^3.0.4",
|
||||
"typeface-roboto": "0.0.75",
|
||||
"uuid": "^8.2.0",
|
||||
"vue": "^2.6.11",
|
||||
@@ -28,8 +30,7 @@
|
||||
"vue-context": "^5.2.0",
|
||||
"vue-directive-tooltip": "^1.6.3",
|
||||
"vue-json-component": "^0.4.1",
|
||||
"vue-slider-component": "^3.2.2",
|
||||
"vue-socket.io": "^3.0.9",
|
||||
"vue-slider-component": "^3.2.11",
|
||||
"vuex": "^3.5.1"
|
||||
},
|
||||
"devDependencies": {
|
||||
@@ -45,7 +46,6 @@
|
||||
"eslint-plugin-vue": "^6.2.2",
|
||||
"vue-cli-plugin-electron-builder": "~2.0.0-rc.4",
|
||||
"vue-cli-plugin-yaml": "^1.0.2",
|
||||
"vue-json-component": "^0.4.1",
|
||||
"vue-template-compiler": "^2.6.11"
|
||||
},
|
||||
"eslintConfig": {
|
||||
|
||||
23
GUI/scripts/enumGenerate.js
Normal file
23
GUI/scripts/enumGenerate.js
Normal file
@@ -0,0 +1,23 @@
|
||||
const fs = require('fs');
|
||||
const path = require('path');
|
||||
|
||||
|
||||
fs.readFile(path.resolve(__dirname,'..','..','tools','odrive','enums.py'), 'utf8', function(err, data) {
|
||||
if (err) throw err;
|
||||
let enumsString = data;
|
||||
let lines = enumsString.split(process.platform == 'win32' ? '\r\n' : '\n');
|
||||
let enums = {};
|
||||
for (const line of lines) {
|
||||
if (line != '' && line[0] != '#') {
|
||||
let name;
|
||||
let value;
|
||||
name = line.split('=')[0];
|
||||
value = line.split('=')[1];
|
||||
enums[name.trim()] = parseInt(value.trim());
|
||||
}
|
||||
}
|
||||
fs.writeFile(path.resolve(__dirname, '../src/assets/odriveEnums.json'), JSON.stringify(enums, null, 4), function(err) {
|
||||
if (err) throw err;
|
||||
});
|
||||
console.log('Wrote ODrive enums to GUI/src/assets/odriveEnums.json');
|
||||
});
|
||||
@@ -9,6 +9,7 @@ import json
|
||||
import time
|
||||
import argparse
|
||||
import logging
|
||||
import math
|
||||
|
||||
# interface for odrive GUI to get data from odrivetool
|
||||
|
||||
@@ -33,7 +34,7 @@ app.config.update(
|
||||
SESSION_COOKIE_SAMESITE='None'
|
||||
)
|
||||
CORS(app, support_credentials=True)
|
||||
Payload.max_decode_packets = 100
|
||||
Payload.max_decode_packets = 500
|
||||
socketio = SocketIO(app, cors_allowed_origins="*", async_mode = "threading")
|
||||
|
||||
#def get_odrive():
|
||||
@@ -176,9 +177,17 @@ def dictFromRO(RO):
|
||||
elif isinstance(RO._remote_attributes[key], fibre.remote_object.RemoteProperty):
|
||||
# grab value of that property
|
||||
# indicate if this property can be written or not
|
||||
returnDict[key] = {"val": str(RO._remote_attributes[key].get_value()),
|
||||
val = str(RO._remote_attributes[key].get_value())
|
||||
_type = str(RO._remote_attributes[key]._property_type.__name__)
|
||||
if val == "inf":
|
||||
val = "Infinity"
|
||||
_type = "str"
|
||||
elif val == "-inf":
|
||||
val = "-Infinity"
|
||||
_type = "str"
|
||||
returnDict[key] = {"val": val,
|
||||
"readonly": not RO._remote_attributes[key]._can_write,
|
||||
"type": str(RO._remote_attributes[key]._property_type.__name__)}
|
||||
"type": _type}
|
||||
elif isinstance(RO._remote_attributes[key], fibre.remote_object.RemoteFunction):
|
||||
# this is a function - do nothing for now.
|
||||
returnDict[key] = "function"
|
||||
@@ -200,6 +209,11 @@ def postVal(odrives, keyList, value, argType):
|
||||
RO.set_value(float(value))
|
||||
elif argType == "boolean":
|
||||
RO.set_value(value)
|
||||
elif argType == "string":
|
||||
if value == "Infinity":
|
||||
RO.set_value(math.inf)
|
||||
elif value == "-Infinity":
|
||||
RO.set_value(-math.inf)
|
||||
else:
|
||||
pass # dont support that type yet
|
||||
except fibre.protocol.ChannelBrokenException:
|
||||
@@ -217,7 +231,12 @@ def getVal(odrives, keyList):
|
||||
if isinstance(RO, fibre.remote_object.RemoteObject):
|
||||
return dictFromRO(RO)
|
||||
else:
|
||||
return RO.get_value()
|
||||
retVal = RO.get_value()
|
||||
if retVal == math.inf:
|
||||
retVal = "Infinity"
|
||||
elif retVal == -math.inf:
|
||||
retVal = "-Infinity"
|
||||
return retVal
|
||||
except fibre.protocol.ChannelBrokenException:
|
||||
handle_disconnect(odrv)
|
||||
except:
|
||||
|
||||
250
GUI/src/App.vue
250
GUI/src/App.vue
@@ -1,7 +1,46 @@
|
||||
<template>
|
||||
<div id="app">
|
||||
<!-- HEADER -->
|
||||
<div class="header">
|
||||
<div class="header" id="header">
|
||||
<button class="dash-button menu-button" @click="toggleMenu">Menu</button>
|
||||
<div class="card menu" id="menu" :style="{top: menuTop}" v-show="showMenu">
|
||||
<button class="dash-button menu-item" @click="exportDash">Export dash</button>
|
||||
<button class="dash-button menu-item" @click="importDashWrapper">
|
||||
Import dash
|
||||
<input
|
||||
type="file"
|
||||
id="inputDash"
|
||||
ref="fileInput"
|
||||
@change="
|
||||
importDashFile($event.target.files);
|
||||
$refs.fileInput.value = null;
|
||||
"
|
||||
value
|
||||
style="display: none"
|
||||
/>
|
||||
</button>
|
||||
<button class="dash-button menu-item" id="importButton" @click="calcImportLeft();calcImportTop();toggleImport()">Import ODrive config</button>
|
||||
<button class="dash-button menu-item" id="exportButton" @click="calcExportLeft();calcExportTop();toggleExport()">Export ODrive config</button>
|
||||
</div>
|
||||
<div class="card import-menu" :style="{top: importTop, left: importLeft}" v-show="showImport">
|
||||
<button v-for="odrive in Object.keys(odrives)" :key="odrive" class="dash-button" @click="importConfigWrapper">
|
||||
{{odrive}}
|
||||
<input
|
||||
type="file"
|
||||
id="inputConfig"
|
||||
ref="fileInputConfig"
|
||||
@change="
|
||||
importConfigFile($event.target, odrive);
|
||||
"
|
||||
onclick="this.value=null"
|
||||
value
|
||||
style="display: none"
|
||||
/>
|
||||
</button>
|
||||
</div>
|
||||
<div class="card export-menu" :style="{top: exportTop, left: exportLeft}" v-show="showExport">
|
||||
<button v-for="odrive in Object.keys(odrives)" :key="odrive" class="dash-button" @click="exportConfig(odrive)">{{odrive}}</button>
|
||||
</div>
|
||||
<button
|
||||
v-for="dash in dashboards"
|
||||
:key="dash.id"
|
||||
@@ -23,21 +62,12 @@
|
||||
{{ dash.name }}
|
||||
</button>
|
||||
<button class="dash-button dash-add" @click="addDash">+</button>
|
||||
<button class="dash-button sample-button" :class="[{ active: sampling === true }]" @click="sampleButton">{{samplingText}}</button>
|
||||
<button class="dash-button" @click="exportDash">export dash</button>
|
||||
<button class="dash-button" @click="importDashWrapper">
|
||||
import dash
|
||||
<input
|
||||
type="file"
|
||||
id="inputDash"
|
||||
ref="fileInput"
|
||||
@change="
|
||||
importDashFile($event.target.files);
|
||||
$refs.fileInput.value = null;
|
||||
"
|
||||
value
|
||||
style="display: none"
|
||||
/>
|
||||
<button
|
||||
class="dash-button sample-button"
|
||||
:class="[{ active: sampling === true }]"
|
||||
@click="sampleButton"
|
||||
>
|
||||
{{ samplingText }}
|
||||
</button>
|
||||
</div>
|
||||
|
||||
@@ -57,6 +87,7 @@
|
||||
:odrives="odrives"
|
||||
></Axis>
|
||||
</div>
|
||||
|
||||
</div>
|
||||
</template>
|
||||
|
||||
@@ -68,6 +99,8 @@ import Wizard from "./views/Wizard.vue";
|
||||
import * as socketio from "./comms/socketio";
|
||||
import { saveAs } from "file-saver";
|
||||
import { v4 as uuidv4 } from "uuid";
|
||||
import { pathsFromTree } from "./lib/utils.js";
|
||||
import { getVal, putVal } from "./lib/odrive_utils.js";
|
||||
|
||||
export default {
|
||||
name: "App",
|
||||
@@ -80,8 +113,20 @@ export default {
|
||||
data: function () {
|
||||
return {
|
||||
//currentDash: "Start",
|
||||
showMenu: false,
|
||||
showImport: false,
|
||||
showExport: false,
|
||||
menuTop: '0px',
|
||||
importTop: '0px',
|
||||
importLeft: '0px',
|
||||
exportTop: '0px',
|
||||
exportLeft: '0px',
|
||||
};
|
||||
},
|
||||
mounted() {
|
||||
var elem = document.getElementById('header');
|
||||
this.menuTop = elem.offsetHeight + 'px';
|
||||
},
|
||||
computed: {
|
||||
currentDashName: function () {
|
||||
//get the appropriate component name from the currentDash variable
|
||||
@@ -129,29 +174,125 @@ export default {
|
||||
samplingText: function () {
|
||||
let ret;
|
||||
if (this.$store.state.sampling) {
|
||||
ret = "stop sampling"
|
||||
}
|
||||
else {
|
||||
ret = "start sampling"
|
||||
ret = "stop sampling";
|
||||
} else {
|
||||
ret = "start sampling";
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
},
|
||||
},
|
||||
methods: {
|
||||
toggleMenu() {
|
||||
this.showMenu = !this.showMenu;
|
||||
if (!this.showMenu) {
|
||||
this.showImport = false;
|
||||
this.showExport = false;
|
||||
}
|
||||
},
|
||||
toggleImport() {
|
||||
this.showImport = !this.showImport;
|
||||
this.showExport = false;
|
||||
},
|
||||
toggleExport() {
|
||||
this.showExport = !this.showExport;
|
||||
this.showImport= false;
|
||||
},
|
||||
importConfigWrapper() {
|
||||
const inputElem = document.getElementById("inputConfig");
|
||||
if (inputElem) {
|
||||
console.log("importing config");
|
||||
inputElem.click();
|
||||
}
|
||||
},
|
||||
importConfigFile(event, odrive) {
|
||||
console.log("Importing config to odrive " + odrive);
|
||||
let file = event.files[0];
|
||||
const reader = new FileReader();
|
||||
// this is ugly, but it gets around scoping problems the "load" callback
|
||||
let importConfig = (config) => {
|
||||
let paths = pathsFromTree(config);
|
||||
for (const path of paths) {
|
||||
let val = config;
|
||||
for(const key of path.split('.')) {
|
||||
val = val[key];
|
||||
}
|
||||
putVal(odrive + '.' + path, val);
|
||||
}
|
||||
console.log("Config imported to odrive " + odrive);
|
||||
};
|
||||
reader.addEventListener("load", function (e) {
|
||||
let importString = e.target.result;
|
||||
importString = importString.replaceAll(" Infinity", '" Infinity"');
|
||||
importString = importString.replaceAll(" -Infinity", '" -Infinity"');
|
||||
importConfig(JSON.parse(importString));
|
||||
});
|
||||
reader.readAsText(file);
|
||||
},
|
||||
exportConfig(odrive) {
|
||||
console.log("Exporting config from odrive " + odrive);
|
||||
let configPaths = [];
|
||||
let exportConfig = {};
|
||||
|
||||
let paramTree = this.$store.state.odriveConfigs.params[odrive];
|
||||
for (const path of pathsFromTree(paramTree)) {
|
||||
if (path.includes('config.') && !path.includes('mapping')) {
|
||||
configPaths.push(path);
|
||||
}
|
||||
}
|
||||
for (const path of configPaths) {
|
||||
let keys = path.split('.');
|
||||
let val = String(getVal(odrive + '.' + path));
|
||||
// super ugly! Need a better way to do this and handle tuples in odrive_utils
|
||||
if (val.includes('True')) {
|
||||
val = true;
|
||||
}
|
||||
else if (val.includes('False')) {
|
||||
val = false;
|
||||
}
|
||||
else if (val.includes('.')) {
|
||||
val = parseFloat(val);
|
||||
}
|
||||
else if (!val.includes(',') && !val.includes('Infinity')){
|
||||
val = parseInt(val);
|
||||
}
|
||||
let obj = exportConfig;
|
||||
for (const key of keys.slice(0,-1)) {
|
||||
if (!Object.keys(obj).includes(key)) {
|
||||
obj[key] = {}
|
||||
}
|
||||
obj = obj[key];
|
||||
}
|
||||
obj[keys.pop()] = val;
|
||||
}
|
||||
let exportString = JSON.stringify(exportConfig, null, 2);
|
||||
if (exportString.includes('"Infinity"')) {
|
||||
console.log("found infinity!");
|
||||
}
|
||||
exportString = exportString.replaceAll('"Infinity"', 'Infinity');
|
||||
exportString = exportString.replaceAll('"-Infinity"', '-Infinity');
|
||||
const blob = new Blob([exportString], {
|
||||
type: "application/json",
|
||||
});
|
||||
saveAs(blob, odrive + '-config.json');
|
||||
},
|
||||
calcImportLeft() {
|
||||
let elem = document.getElementById('menu');
|
||||
this.importLeft = elem.offsetWidth + 'px';
|
||||
},
|
||||
calcImportTop() {
|
||||
this.importTop = document.getElementById('importButton').getBoundingClientRect().top + 'px';
|
||||
},
|
||||
calcExportLeft() {
|
||||
let elem = document.getElementById('menu')
|
||||
this.exportLeft = elem.offsetWidth + 'px';
|
||||
},
|
||||
calcExportTop() {
|
||||
this.exportTop = document.getElementById('exportButton').getBoundingClientRect().top + 'px';
|
||||
},
|
||||
changeDash(dashName) {
|
||||
console.log(dashName);
|
||||
this.$store.commit("setDash", dashName);
|
||||
},
|
||||
//updateOdrives() {
|
||||
// if (this.$store.state.serverConnected == true) {
|
||||
//} && this.sampling == false) {
|
||||
// this.$store.dispatch("getOdrives");
|
||||
// }
|
||||
//setTimeout(() => {
|
||||
// this.updateOdrives();
|
||||
//}, 1000);
|
||||
//console.log("updating data...");
|
||||
//},
|
||||
addDash() {
|
||||
let dashname = "Dashboard " + (this.dashboards.length - 2);
|
||||
this.dashboards.push({
|
||||
@@ -217,12 +358,11 @@ export default {
|
||||
sampleButton() {
|
||||
if (this.$store.state.sampling) {
|
||||
// sampling acttive, stop
|
||||
socketio.sendEvent({
|
||||
socketio.sendEvent({
|
||||
type: "stopSampling",
|
||||
});
|
||||
this.$store.state.sampling = false;
|
||||
}
|
||||
else {
|
||||
} else {
|
||||
// sampling inactive, start sampling
|
||||
socketio.sendEvent({
|
||||
type: "sampledVarNames",
|
||||
@@ -273,13 +413,13 @@ export default {
|
||||
|
||||
// to allow running as web app
|
||||
if (window.ipcRenderer != undefined) {
|
||||
window.ipcRenderer.on('server-stdout', (event, arg) => {
|
||||
this.$store.commit('logServerMessage', arg);
|
||||
window.ipcRenderer.on("server-stdout", (event, arg) => {
|
||||
this.$store.commit("logServerMessage", arg);
|
||||
});
|
||||
window.ipcRenderer.on('server-stderr', (event, arg) => {
|
||||
this.$store.commit('logServerMessage', arg);
|
||||
window.ipcRenderer.on("server-stderr", (event, arg) => {
|
||||
this.$store.commit("logServerMessage", arg);
|
||||
});
|
||||
window.ipcRenderer.send('start-server');
|
||||
window.ipcRenderer.send("start-server");
|
||||
}
|
||||
},
|
||||
};
|
||||
@@ -343,6 +483,10 @@ button {
|
||||
background-color: var(--bg-color);
|
||||
}
|
||||
|
||||
.menu-item {
|
||||
text-align: left;
|
||||
}
|
||||
|
||||
.active {
|
||||
color: #000000;
|
||||
background-color: var(--bg-color);
|
||||
@@ -395,4 +539,32 @@ button {
|
||||
padding: 5px 10px;
|
||||
}
|
||||
|
||||
.menu-button {
|
||||
border-right: 1px solid grey;
|
||||
}
|
||||
|
||||
.menu {
|
||||
position: absolute;
|
||||
margin: 0;
|
||||
padding: 0;
|
||||
left: 0;
|
||||
display: flex;
|
||||
flex-direction: column;
|
||||
}
|
||||
|
||||
.import-menu {
|
||||
position: absolute;
|
||||
margin: 0;
|
||||
padding: 0;
|
||||
display: flex;
|
||||
flex-direction: column;
|
||||
}
|
||||
|
||||
.export-menu {
|
||||
position: absolute;
|
||||
margin: 0;
|
||||
padding: 0;
|
||||
display: flex;
|
||||
flex-direction: column;
|
||||
}
|
||||
</style>
|
||||
|
||||
@@ -102,11 +102,11 @@
|
||||
"vars": [
|
||||
{
|
||||
"path": "odrives.odrive0.axis0.controller.pos_setpoint",
|
||||
"color": "#195bd7"
|
||||
"color": "#1f77b4"
|
||||
},
|
||||
{
|
||||
"path": "odrives.odrive0.axis0.encoder.pos_estimate",
|
||||
"color": "#d6941a"
|
||||
"color": "#ff7f0e"
|
||||
}
|
||||
]
|
||||
},
|
||||
@@ -115,11 +115,11 @@
|
||||
"vars": [
|
||||
{
|
||||
"path": "odrives.odrive0.axis0.controller.vel_setpoint",
|
||||
"color": "#195bd7"
|
||||
"color": "#1f77b4"
|
||||
},
|
||||
{
|
||||
"path": "odrives.odrive0.axis0.encoder.vel_estimate",
|
||||
"color": "#d6941a"
|
||||
"color": "#ff7f0e"
|
||||
}
|
||||
]
|
||||
}
|
||||
|
||||
@@ -102,11 +102,11 @@
|
||||
"vars": [
|
||||
{
|
||||
"path": "odrives.odrive0.axis0.controller.input_pos",
|
||||
"color": "#195bd7"
|
||||
"color": "#1f77b4"
|
||||
},
|
||||
{
|
||||
"path": "odrives.odrive0.axis0.encoder.pos_estimate",
|
||||
"color": "#d6941a"
|
||||
"color": "#ff7f0e"
|
||||
}
|
||||
]
|
||||
},
|
||||
@@ -115,11 +115,11 @@
|
||||
"vars": [
|
||||
{
|
||||
"path": "odrives.odrive0.axis0.controller.vel_setpoint",
|
||||
"color": "#195bd7"
|
||||
"color": "#1f77b4"
|
||||
},
|
||||
{
|
||||
"path": "odrives.odrive0.axis0.encoder.vel_estimate",
|
||||
"color": "#d6941a"
|
||||
"color": "#ff7f0e"
|
||||
}
|
||||
]
|
||||
}
|
||||
|
||||
@@ -1,131 +1,123 @@
|
||||
{
|
||||
"GPIO_MODE_DIGITAL" : 0,
|
||||
"GPIO_MODE_DIGITAL_PULL_UP" : 1,
|
||||
"GPIO_MODE_DIGITAL_PULL_DOWN" : 2,
|
||||
"GPIO_MODE_ANALOG_IN" : 3,
|
||||
"GPIO_MODE_UART0" : 4,
|
||||
"GPIO_MODE_UART1" : 5,
|
||||
"GPIO_MODE_UART2" : 6,
|
||||
"GPIO_MODE_CAN0" : 7,
|
||||
"GPIO_MODE_I2C0" : 8,
|
||||
"GPIO_MODE_SPI0" : 9,
|
||||
"GPIO_MODE_PWM0" : 10,
|
||||
"GPIO_MODE_ENC0" : 11,
|
||||
"GPIO_MODE_ENC1" : 12,
|
||||
"GPIO_MODE_ENC2" : 13,
|
||||
|
||||
"PROTOCOL_SIMPLE" : 0,
|
||||
|
||||
"AXIS_STATE_UNDEFINED" : 0,
|
||||
"AXIS_STATE_IDLE" : 1,
|
||||
"AXIS_STATE_STARTUP_SEQUENCE" : 2,
|
||||
"AXIS_STATE_FULL_CALIBRATION_SEQUENCE" : 3,
|
||||
"AXIS_STATE_MOTOR_CALIBRATION" : 4,
|
||||
"AXIS_STATE_SENSORLESS_CONTROL" : 5,
|
||||
"AXIS_STATE_ENCODER_INDEX_SEARCH" : 6,
|
||||
"AXIS_STATE_ENCODER_OFFSET_CALIBRATION" : 7,
|
||||
"AXIS_STATE_CLOSED_LOOP_CONTROL" : 8,
|
||||
"AXIS_STATE_LOCKIN_SPIN" : 9,
|
||||
"AXIS_STATE_ENCODER_DIR_FIND" : 10,
|
||||
"AXIS_STATE_HOMING" : 11,
|
||||
|
||||
"ENCODER_MODE_INCREMENTAL" : 0,
|
||||
"ENCODER_MODE_HALL" : 1,
|
||||
"ENCODER_MODE_SINCOS" : 2,
|
||||
"ENCODER_MODE_SPI_ABS_CUI" : 256,
|
||||
"ENCODER_MODE_SPI_ABS_AMS" : 257,
|
||||
"ENCODER_MODE_SPI_ABS_AEAT" : 258,
|
||||
"ENCODER_MODE_SPI_ABS_RLS" : 259,
|
||||
|
||||
"CONTROL_MODE_VOLTAGE_CONTROL" : 0,
|
||||
"CONTROL_MODE_TORQUE_CONTROL" : 1,
|
||||
"CONTROL_MODE_VELOCITY_CONTROL" : 2,
|
||||
"CONTROL_MODE_POSITION_CONTROL" : 3,
|
||||
|
||||
"INPUT_MODE_INACTIVE" : 0,
|
||||
"INPUT_MODE_PASSTHROUGH" : 1,
|
||||
"INPUT_MODE_VEL_RAMP" : 2,
|
||||
"INPUT_MODE_POS_FILTER" : 3,
|
||||
"INPUT_MODE_MIX_CHANNELS" : 4,
|
||||
"INPUT_MODE_TRAP_TRAJ" : 5,
|
||||
"INPUT_MODE_TORQUE_RAMP" : 6,
|
||||
"INPUT_MODE_MIRROR" : 7,
|
||||
|
||||
"MOTOR_TYPE_HIGH_CURRENT" : 0,
|
||||
"MOTOR_TYPE_GIMBAL" : 2,
|
||||
"MOTOR_TYPE_ACIM" : 3,
|
||||
|
||||
"CAN_ERROR_NONE" : 0,
|
||||
"CAN_ERROR_DUPLICATE_CAN_IDS" : 1,
|
||||
|
||||
"AXIS_ERROR_NONE" : 0,
|
||||
"AXIS_ERROR_INVALID_STATE" : 1,
|
||||
"AXIS_ERROR_DC_BUS_UNDER_VOLTAGE" : 2,
|
||||
"AXIS_ERROR_DC_BUS_OVER_VOLTAGE" : 4,
|
||||
"AXIS_ERROR_CURRENT_MEASUREMENT_TIMEOUT" : 8,
|
||||
"AXIS_ERROR_BRAKE_RESISTOR_DISARMED" : 16,
|
||||
"AXIS_ERROR_MOTOR_DISARMED" : 32,
|
||||
"AXIS_ERROR_MOTOR_FAILED" : 64,
|
||||
"AXIS_ERROR_SENSORLESS_ESTIMATOR_FAILED" : 128,
|
||||
"AXIS_ERROR_ENCODER_FAILED" : 256,
|
||||
"AXIS_ERROR_CONTROLLER_FAILED" : 512,
|
||||
"AXIS_ERROR_POS_CTRL_DURING_SENSORLESS" : 1024,
|
||||
"AXIS_ERROR_WATCHDOG_TIMER_EXPIRED" : 2048,
|
||||
"AXIS_ERROR_MIN_ENDSTOP_PRESSED" : 4096,
|
||||
"AXIS_ERROR_MAX_ENDSTOP_PRESSED" : 8192,
|
||||
"AXIS_ERROR_ESTOP_REQUESTED" : 16384,
|
||||
"AXIS_ERROR_HOMING_WITHOUT_ENDSTOP" : 131072,
|
||||
"AXIS_ERROR_OVER_TEMP" : 262144,
|
||||
|
||||
"LOCKIN_STATE_INACTIVE" : 0,
|
||||
"LOCKIN_STATE_RAMP" : 1,
|
||||
"LOCKIN_STATE_ACCELERATE" : 2,
|
||||
"LOCKIN_STATE_CONST_VEL" : 3,
|
||||
|
||||
"MOTOR_ERROR_NONE" : 0,
|
||||
"MOTOR_ERROR_PHASE_RESISTANCE_OUT_OF_RANGE" : 1,
|
||||
"MOTOR_ERROR_PHASE_INDUCTANCE_OUT_OF_RANGE" : 2,
|
||||
"MOTOR_ERROR_ADC_FAILED" : 4,
|
||||
"MOTOR_ERROR_DRV_FAULT" : 8,
|
||||
"MOTOR_ERROR_CONTROL_DEADLINE_MISSED" : 16,
|
||||
"MOTOR_ERROR_NOT_IMPLEMENTED_MOTOR_TYPE" : 32,
|
||||
"MOTOR_ERROR_BRAKE_CURRENT_OUT_OF_RANGE" : 64,
|
||||
"MOTOR_ERROR_MODULATION_MAGNITUDE" : 128,
|
||||
"MOTOR_ERROR_BRAKE_DEADTIME_VIOLATION" : 256,
|
||||
"MOTOR_ERROR_UNEXPECTED_TIMER_CALLBACK" : 512,
|
||||
"MOTOR_ERROR_CURRENT_SENSE_SATURATION" : 1024,
|
||||
"MOTOR_ERROR_CURRENT_LIMIT_VIOLATION" : 4096,
|
||||
"MOTOR_ERROR_BRAKE_DUTY_CYCLE_NAN" : 8192,
|
||||
"MOTOR_ERROR_DC_BUS_OVER_REGEN_CURRENT" : 16384,
|
||||
"MOTOR_ERROR_DC_BUS_OVER_CURRENT" : 32768,
|
||||
"MOTOR_ERROR_MODULATION_IS_NAN" : 65536,
|
||||
"MOTOR_ERROR_MOTOR_THERMISTOR_OVER_TEMP" : 131072,
|
||||
"MOTOR_ERROR_FET_THERMISTOR_OVER_TEMP" : 262144,
|
||||
|
||||
"ARMED_STATE_DISARMED" : 0,
|
||||
"ARMED_STATE_WAITING_FOR_TIMINGS" : 1,
|
||||
"ARMED_STATE_WAITING_FOR_UPDATE" : 2,
|
||||
"ARMED_STATE_ARMED" : 3,
|
||||
|
||||
"CONTROLLER_ERROR_NONE" : 0,
|
||||
"CONTROLLER_ERROR_OVERSPEED" : 1,
|
||||
"CONTROLLER_ERROR_INVALID_INPUT_MODE" : 2,
|
||||
"CONTROLLER_ERROR_UNSTABLE_GAIN" : 4,
|
||||
"CONTROLLER_ERROR_INVALID_MIRROR_AXIS" : 8,
|
||||
"CONTROLLER_ERROR_INVALID_LOAD_ENCODER" : 16,
|
||||
"CONTROLLER_ERROR_INVALID_ESTIMATE" : 32,
|
||||
|
||||
"ENCODER_ERROR_NONE" : 0,
|
||||
"ENCODER_ERROR_UNSTABLE_GAIN" : 1,
|
||||
"ENCODER_ERROR_CPR_POLEPAIRS_MISMATCH" : 2,
|
||||
"ENCODER_ERROR_NO_RESPONSE" : 4,
|
||||
"ENCODER_ERROR_UNSUPPORTED_ENCODER_MODE" : 8,
|
||||
"ENCODER_ERROR_ILLEGAL_HALL_STATE" : 16,
|
||||
"ENCODER_ERROR_INDEX_NOT_FOUND_YET" : 32,
|
||||
"ENCODER_ERROR_ABS_SPI_TIMEOUT" : 64,
|
||||
"ENCODER_ERROR_ABS_SPI_COM_FAIL" : 128,
|
||||
"ENCODER_ERROR_ABS_SPI_NOT_READY" : 256,
|
||||
|
||||
"SENSORLESS_ESTIMATOR_ERROR_NONE" : 0,
|
||||
"SENSORLESS_ESTIMATOR_ERROR_UNSTABLE_GAIN" : 1
|
||||
"GPIO_MODE_DIGITAL": 0,
|
||||
"GPIO_MODE_DIGITAL_PULL_UP": 1,
|
||||
"GPIO_MODE_DIGITAL_PULL_DOWN": 2,
|
||||
"GPIO_MODE_ANALOG_IN": 3,
|
||||
"GPIO_MODE_UART_A": 4,
|
||||
"GPIO_MODE_UART_B": 5,
|
||||
"GPIO_MODE_UART_C": 6,
|
||||
"GPIO_MODE_CAN_A": 7,
|
||||
"GPIO_MODE_I2C_A": 8,
|
||||
"GPIO_MODE_SPI_A": 9,
|
||||
"GPIO_MODE_PWM": 10,
|
||||
"GPIO_MODE_ENC0": 11,
|
||||
"GPIO_MODE_ENC1": 12,
|
||||
"GPIO_MODE_ENC2": 13,
|
||||
"GPIO_MODE_MECH_BRAKE": 14,
|
||||
"GPIO_MODE_STATUS": 15,
|
||||
"PROTOCOL_SIMPLE": 1,
|
||||
"AXIS_STATE_UNDEFINED": 0,
|
||||
"AXIS_STATE_IDLE": 1,
|
||||
"AXIS_STATE_STARTUP_SEQUENCE": 2,
|
||||
"AXIS_STATE_FULL_CALIBRATION_SEQUENCE": 3,
|
||||
"AXIS_STATE_MOTOR_CALIBRATION": 4,
|
||||
"AXIS_STATE_ENCODER_INDEX_SEARCH": 6,
|
||||
"AXIS_STATE_ENCODER_OFFSET_CALIBRATION": 7,
|
||||
"AXIS_STATE_CLOSED_LOOP_CONTROL": 8,
|
||||
"AXIS_STATE_LOCKIN_SPIN": 9,
|
||||
"AXIS_STATE_ENCODER_DIR_FIND": 10,
|
||||
"AXIS_STATE_HOMING": 11,
|
||||
"AXIS_STATE_ENCODER_HALL_POLARITY_CALIBRATION": 12,
|
||||
"AXIS_STATE_ENCODER_HALL_PHASE_CALIBRATION": 13,
|
||||
"ENCODER_MODE_INCREMENTAL": 0,
|
||||
"ENCODER_MODE_HALL": 1,
|
||||
"ENCODER_MODE_SINCOS": 2,
|
||||
"ENCODER_MODE_SPI_ABS_CUI": 256,
|
||||
"ENCODER_MODE_SPI_ABS_AMS": 257,
|
||||
"ENCODER_MODE_SPI_ABS_AEAT": 258,
|
||||
"ENCODER_MODE_SPI_ABS_RLS": 259,
|
||||
"ENCODER_MODE_SPI_ABS_MA732": 260,
|
||||
"CONTROL_MODE_VOLTAGE_CONTROL": 0,
|
||||
"CONTROL_MODE_TORQUE_CONTROL": 1,
|
||||
"CONTROL_MODE_VELOCITY_CONTROL": 2,
|
||||
"CONTROL_MODE_POSITION_CONTROL": 3,
|
||||
"INPUT_MODE_INACTIVE": 0,
|
||||
"INPUT_MODE_PASSTHROUGH": 1,
|
||||
"INPUT_MODE_VEL_RAMP": 2,
|
||||
"INPUT_MODE_POS_FILTER": 3,
|
||||
"INPUT_MODE_MIX_CHANNELS": 4,
|
||||
"INPUT_MODE_TRAP_TRAJ": 5,
|
||||
"INPUT_MODE_TORQUE_RAMP": 6,
|
||||
"INPUT_MODE_MIRROR": 7,
|
||||
"MOTOR_TYPE_HIGH_CURRENT": 0,
|
||||
"MOTOR_TYPE_GIMBAL": 2,
|
||||
"MOTOR_TYPE_ACIM": 3,
|
||||
"ODRIVE_ERROR_NONE": 0,
|
||||
"ODRIVE_ERROR_CONTROL_ITERATION_MISSED": 1,
|
||||
"ODRIVE_ERROR_DC_BUS_UNDER_VOLTAGE": 2,
|
||||
"ODRIVE_ERROR_DC_BUS_OVER_VOLTAGE": 4,
|
||||
"ODRIVE_ERROR_DC_BUS_OVER_REGEN_CURRENT": 8,
|
||||
"ODRIVE_ERROR_DC_BUS_OVER_CURRENT": 16,
|
||||
"ODRIVE_ERROR_BRAKE_DEADTIME_VIOLATION": 32,
|
||||
"ODRIVE_ERROR_BRAKE_DUTY_CYCLE_NAN": 64,
|
||||
"ODRIVE_ERROR_INVALID_BRAKE_RESISTANCE": 128,
|
||||
"CAN_ERROR_NONE": 0,
|
||||
"CAN_ERROR_DUPLICATE_CAN_IDS": 1,
|
||||
"AXIS_ERROR_NONE": 0,
|
||||
"AXIS_ERROR_INVALID_STATE": 1,
|
||||
"AXIS_ERROR_WATCHDOG_TIMER_EXPIRED": 2048,
|
||||
"AXIS_ERROR_MIN_ENDSTOP_PRESSED": 4096,
|
||||
"AXIS_ERROR_MAX_ENDSTOP_PRESSED": 8192,
|
||||
"AXIS_ERROR_ESTOP_REQUESTED": 16384,
|
||||
"AXIS_ERROR_HOMING_WITHOUT_ENDSTOP": 131072,
|
||||
"AXIS_ERROR_OVER_TEMP": 262144,
|
||||
"MOTOR_ERROR_NONE": 0,
|
||||
"MOTOR_ERROR_PHASE_RESISTANCE_OUT_OF_RANGE": 1,
|
||||
"MOTOR_ERROR_PHASE_INDUCTANCE_OUT_OF_RANGE": 2,
|
||||
"MOTOR_ERROR_DRV_FAULT": 8,
|
||||
"MOTOR_ERROR_CONTROL_DEADLINE_MISSED": 16,
|
||||
"MOTOR_ERROR_MODULATION_MAGNITUDE": 128,
|
||||
"MOTOR_ERROR_CURRENT_SENSE_SATURATION": 1024,
|
||||
"MOTOR_ERROR_CURRENT_LIMIT_VIOLATION": 4096,
|
||||
"MOTOR_ERROR_MODULATION_IS_NAN": 65536,
|
||||
"MOTOR_ERROR_MOTOR_THERMISTOR_OVER_TEMP": 131072,
|
||||
"MOTOR_ERROR_FET_THERMISTOR_OVER_TEMP": 262144,
|
||||
"MOTOR_ERROR_TIMER_UPDATE_MISSED": 524288,
|
||||
"MOTOR_ERROR_CURRENT_MEASUREMENT_UNAVAILABLE": 1048576,
|
||||
"MOTOR_ERROR_CONTROLLER_FAILED": 2097152,
|
||||
"MOTOR_ERROR_I_BUS_OUT_OF_RANGE": 4194304,
|
||||
"MOTOR_ERROR_BRAKE_RESISTOR_DISARMED": 8388608,
|
||||
"MOTOR_ERROR_SYSTEM_LEVEL": 16777216,
|
||||
"MOTOR_ERROR_BAD_TIMING": 33554432,
|
||||
"MOTOR_ERROR_UNKNOWN_PHASE_ESTIMATE": 67108864,
|
||||
"MOTOR_ERROR_UNKNOWN_PHASE_VEL": 134217728,
|
||||
"MOTOR_ERROR_UNKNOWN_TORQUE": 268435456,
|
||||
"MOTOR_ERROR_UNKNOWN_CURRENT_COMMAND": 536870912,
|
||||
"MOTOR_ERROR_UNKNOWN_CURRENT_MEASUREMENT": 1073741824,
|
||||
"MOTOR_ERROR_UNKNOWN_VBUS_VOLTAGE": 2147483648,
|
||||
"MOTOR_ERROR_UNKNOWN_VOLTAGE_COMMAND": 4294967296,
|
||||
"MOTOR_ERROR_UNKNOWN_GAINS": 8589934592,
|
||||
"MOTOR_ERROR_CONTROLLER_INITIALIZING": 17179869184,
|
||||
"MOTOR_ERROR_UNBALANCED_PHASES": 34359738368,
|
||||
"CONTROLLER_ERROR_NONE": 0,
|
||||
"CONTROLLER_ERROR_OVERSPEED": 1,
|
||||
"CONTROLLER_ERROR_INVALID_INPUT_MODE": 2,
|
||||
"CONTROLLER_ERROR_UNSTABLE_GAIN": 4,
|
||||
"CONTROLLER_ERROR_INVALID_MIRROR_AXIS": 8,
|
||||
"CONTROLLER_ERROR_INVALID_LOAD_ENCODER": 16,
|
||||
"CONTROLLER_ERROR_INVALID_ESTIMATE": 32,
|
||||
"ENCODER_ERROR_NONE": 0,
|
||||
"ENCODER_ERROR_UNSTABLE_GAIN": 1,
|
||||
"ENCODER_ERROR_CPR_POLEPAIRS_MISMATCH": 2,
|
||||
"ENCODER_ERROR_NO_RESPONSE": 4,
|
||||
"ENCODER_ERROR_UNSUPPORTED_ENCODER_MODE": 8,
|
||||
"ENCODER_ERROR_ILLEGAL_HALL_STATE": 16,
|
||||
"ENCODER_ERROR_INDEX_NOT_FOUND_YET": 32,
|
||||
"ENCODER_ERROR_ABS_SPI_TIMEOUT": 64,
|
||||
"ENCODER_ERROR_ABS_SPI_COM_FAIL": 128,
|
||||
"ENCODER_ERROR_ABS_SPI_NOT_READY": 256,
|
||||
"ENCODER_ERROR_HALL_NOT_CALIBRATED_YET": 512,
|
||||
"SENSORLESS_ESTIMATOR_ERROR_NONE": 0,
|
||||
"SENSORLESS_ESTIMATOR_ERROR_UNSTABLE_GAIN": 1,
|
||||
"SENSORLESS_ESTIMATOR_ERROR_UNKNOWN_CURRENT_MEASUREMENT": 2
|
||||
}
|
||||
@@ -18,7 +18,8 @@
|
||||
"mode": null,
|
||||
"use_index": null,
|
||||
"cpr": null,
|
||||
"calib_scan_distance": null
|
||||
"calib_scan_distance": null,
|
||||
"abs_spi_cs_gpio_pin": null
|
||||
}
|
||||
},
|
||||
"controller": {
|
||||
@@ -53,7 +54,8 @@
|
||||
"mode": null,
|
||||
"use_index": null,
|
||||
"cpr": null,
|
||||
"calib_scan_distance": null
|
||||
"calib_scan_distance": null,
|
||||
"abs_spi_cs_gpio_pin": null
|
||||
}
|
||||
},
|
||||
"controller": {
|
||||
|
||||
@@ -1,24 +1,32 @@
|
||||
<template>
|
||||
<div
|
||||
class="axis"
|
||||
@click.self="showError = !showError;"
|
||||
:class="{inactive: !connected, noError: !error, error: error}"
|
||||
@click.self="showError = !showError"
|
||||
:class="{ inactive: !connected, noError: !error, error: error }"
|
||||
>
|
||||
{{ axis }}
|
||||
<div v-show="showError" class="error-popup card" @click.self="showError = !showError">
|
||||
<clear-errors :data="{axis: axis}"/>
|
||||
<div
|
||||
v-show="showError"
|
||||
class="error-popup card"
|
||||
@click.self="showError = !showError"
|
||||
>
|
||||
<clear-errors :data="{ axis: axis }" />
|
||||
axis:
|
||||
<span :class="{ noError: !axisError, error: axisError}">{{axisErrorMsg}}</span>
|
||||
<span :class="{ noError: !axisError, error: axisError }">{{
|
||||
axisErrorMsg
|
||||
}}</span>
|
||||
<br />motor:
|
||||
<span :class="{ noError: !motorError, error: motorError}">{{motorErrorMsg}}</span>
|
||||
<span :class="{ noError: !motorError, error: motorError }">{{
|
||||
motorErrorMsg
|
||||
}}</span>
|
||||
<br />encoder:
|
||||
<span
|
||||
:class="{ noError: !encoderError, error: encoderError}"
|
||||
>{{encoderErrorMsg}}</span>
|
||||
<span :class="{ noError: !encoderError, error: encoderError }">{{
|
||||
encoderErrorMsg
|
||||
}}</span>
|
||||
<br />controller:
|
||||
<span
|
||||
:class="{ noError: !controllerError, error: controllerError}"
|
||||
>{{controllerErrorMsg}}</span>
|
||||
<span :class="{ noError: !controllerError, error: controllerError }">{{
|
||||
controllerErrorMsg
|
||||
}}</span>
|
||||
</div>
|
||||
</div>
|
||||
</template>
|
||||
@@ -28,72 +36,6 @@ import odriveEnums from "../assets/odriveEnums.json";
|
||||
import clearErrors from "./clearErrors.vue";
|
||||
import { getVal, fetchParam } from "../lib/odrive_utils";
|
||||
|
||||
const axisErrors = {
|
||||
0x00000000: "AXIS_ERROR_NONE",
|
||||
0x00000001: "AXIS_ERROR_INVALID_STATE",
|
||||
0x00000002: "AXIS_ERROR_DC_BUS_UNDER_VOLTAGE",
|
||||
0x00000004: "AXIS_ERROR_DC_BUS_OVER_VOLTAGE",
|
||||
0x00000008: "AXIS_ERROR_CURRENT_MEASUREMENT_TIMEOUT",
|
||||
0x00000010: "AXIS_ERROR_BRAKE_RESISTOR_DISARMED",
|
||||
0x00000020: "AXIS_ERROR_MOTOR_DISARMED",
|
||||
0x00000040: "AXIS_ERROR_MOTOR_FAILED",
|
||||
0x00000080: "AXIS_ERROR_SENSORLESS_ESTIMATOR_FAILED",
|
||||
0x00000100: "AXIS_ERROR_ENCODER_FAILED",
|
||||
0x00000200: "AXIS_ERROR_CONTROLLER_FAILED",
|
||||
0x00000400: "AXIS_ERROR_POS_CTRL_DURING_SENSORLESS",
|
||||
0x00000800: "AXIS_ERROR_WATCHDOG_TIMER_EXPIRED",
|
||||
0x00001000: "AXIS_ERROR_MIN_ENDSTOP_PRESSED",
|
||||
0x00002000: "AXIS_ERROR_MAX_ENDSTOP_PRESSED",
|
||||
0x00004000: "AXIS_ERROR_ESTOP_REQUESTED",
|
||||
0x00020000: "AXIS_ERROR_HOMING_WITHOUT_ENDSTOP",
|
||||
0x00040000: "AXIS_ERROR_OVER_TEMP",
|
||||
};
|
||||
|
||||
const motorErrors = {
|
||||
0x00000000: "MOTOR_ERROR_NONE",
|
||||
0x00000001: "MOTOR_ERROR_PHASE_RESISTANCE_OUT_OF_RANGE",
|
||||
0x00000002: "MOTOR_ERROR_PHASE_INDUCTANCE_OUT_OF_RANGE",
|
||||
0x00000004: "MOTOR_ERROR_ADC_FAILED",
|
||||
0x00000008: "MOTOR_ERROR_DRV_FAULT",
|
||||
0x00000010: "MOTOR_ERROR_CONTROL_DEADLINE_MISSED",
|
||||
0x00000020: "MOTOR_ERROR_NOT_IMPLEMENTED_MOTOR_TYPE",
|
||||
0x00000040: "MOTOR_ERROR_BRAKE_CURRENT_OUT_OF_RANGE",
|
||||
0x00000080: "MOTOR_ERROR_MODULATION_MAGNITUDE",
|
||||
0x00000100: "MOTOR_ERROR_BRAKE_DEADTIME_VIOLATION",
|
||||
0x00000200: "MOTOR_ERROR_UNEXPECTED_TIMER_CALLBACK",
|
||||
0x00000400: "MOTOR_ERROR_CURRENT_SENSE_SATURATION",
|
||||
0x00001000: "MOTOR_ERROR_CURRENT_LIMIT_VIOLATION",
|
||||
0x00002000: "MOTOR_ERROR_BRAKE_DUTY_CYCLE_NAN",
|
||||
0x00004000: "MOTOR_ERROR_DC_BUS_OVER_REGEN_CURRENT",
|
||||
0x00008000: "MOTOR_ERROR_DC_BUS_OVER_CURRENT",
|
||||
0x00010000: "MOTOR_ERROR_MODULATION_IS_NAN",
|
||||
0x00020000: "MOTOR_ERROR_MOTOR_THERMISTOR_OVER_TEMP",
|
||||
0x00040000: "MOTOR_ERROR_FET_THERMISTOR_OVER_TEMP",
|
||||
};
|
||||
|
||||
let encoderErrors = {
|
||||
0x00000000: "ENCODER_ERROR_NONE",
|
||||
0x00000001: "ENCODER_ERROR_UNSTABLE_GAIN",
|
||||
0x00000002: "ENCODER_ERROR_CPR_POLEPAIRS_MISMATCH",
|
||||
0x00000004: "ENCODER_ERROR_NO_RESPONSE",
|
||||
0x00000008: "ENCODER_ERROR_UNSUPPORTED_ENCODER_MODE",
|
||||
0x00000010: "ENCODER_ERROR_ILLEGAL_HALL_STATE",
|
||||
0x00000020: "ENCODER_ERROR_INDEX_NOT_FOUND_YET",
|
||||
0x00000040: "ENCODER_ERROR_ABS_SPI_TIMEOUT",
|
||||
0x00000080: "ENCODER_ERROR_ABS_SPI_COM_FAIL",
|
||||
0x00000100: "ENCODER_ERROR_ABS_SPI_NOT_READY",
|
||||
};
|
||||
|
||||
let controllerErrors = {
|
||||
0x00000000: "CONTROLLER_ERROR_NONE",
|
||||
0x00000001: "CONTROLLER_ERROR_OVERSPEED",
|
||||
0x00000002: "CONTROLLER_ERROR_INVALID_INPUT_MODE",
|
||||
0x00000004: "CONTROLLER_ERROR_UNSTABLE_GAIN",
|
||||
0x00000008: "CONTROLLER_ERROR_INVALID_MIRROR_AXIS",
|
||||
0x00000010: "CONTROLLER_ERROR_INVALID_LOAD_ENCODER",
|
||||
0x00000020: "CONTROLLER_ERROR_INVALID_ESTIMATE",
|
||||
};
|
||||
|
||||
export default {
|
||||
name: "Axis",
|
||||
components: {
|
||||
@@ -109,12 +51,30 @@ export default {
|
||||
encoderErr: undefined,
|
||||
};
|
||||
},
|
||||
methods: {
|
||||
getErrorString(errCode, errType) {
|
||||
let retMsg = "none";
|
||||
|
||||
if (errCode != 0) {
|
||||
// we got an error!
|
||||
// mask errors depending on which page is active
|
||||
let errs = [];
|
||||
for (const [name, value] of Object.entries(odriveEnums)) {
|
||||
if (name.includes(errType) && errCode & value) {
|
||||
errs.push(name);
|
||||
}
|
||||
}
|
||||
retMsg = errs.join(", ");
|
||||
}
|
||||
|
||||
return retMsg;
|
||||
},
|
||||
},
|
||||
computed: {
|
||||
connected() {
|
||||
return this.$store.state.ODrivesConnected[this.axis.split('.')[0]];
|
||||
return this.$store.state.ODrivesConnected[this.axis.split(".")[0]];
|
||||
},
|
||||
axisErrorMsg() {
|
||||
let retMsg = "none";
|
||||
let errCode = this.axisErr;
|
||||
|
||||
if (this.$store.state.currentDash == "Wizard") {
|
||||
@@ -122,22 +82,9 @@ export default {
|
||||
errCode &= ~odriveEnums.AXIS_ERROR_ENCODER_FAILED;
|
||||
}
|
||||
|
||||
if (errCode != 0) {
|
||||
// we got an error!
|
||||
// mask errors depending on which page is active
|
||||
let errs = [];
|
||||
for (const errKey of Object.keys(axisErrors)) {
|
||||
if (errCode & errKey) {
|
||||
errs.push(axisErrors[errKey]);
|
||||
}
|
||||
}
|
||||
retMsg = errs.join(', ');
|
||||
}
|
||||
|
||||
return retMsg;
|
||||
return this.getErrorString(errCode, 'AXIS_ERROR');
|
||||
},
|
||||
motorErrorMsg() {
|
||||
let retMsg = "none";
|
||||
let errCode = this.motorErr;
|
||||
|
||||
if (this.$store.state.currentDash == "Wizard") {
|
||||
@@ -145,21 +92,9 @@ export default {
|
||||
errCode &= ~odriveEnums.MOTOR_ERROR_PHASE_INDUCTANCE_OUT_OF_RANGE;
|
||||
}
|
||||
|
||||
if (errCode != 0) {
|
||||
// we got an error!
|
||||
let errs = [];
|
||||
for (const errKey of Object.keys(motorErrors)) {
|
||||
if (errCode & errKey) {
|
||||
errs.push(motorErrors[errKey]);
|
||||
}
|
||||
}
|
||||
retMsg = errs.join(', ');
|
||||
}
|
||||
|
||||
return retMsg;
|
||||
return this.getErrorString(errCode, 'MOTOR_ERROR');
|
||||
},
|
||||
encoderErrorMsg() {
|
||||
let retMsg = "none";
|
||||
let errCode = this.encoderErr;
|
||||
|
||||
if (this.$store.state.currentDash == "Wizard") {
|
||||
@@ -167,35 +102,12 @@ export default {
|
||||
errCode &= ~odriveEnums.ENCODER_ERROR_NO_RESPONSE;
|
||||
}
|
||||
|
||||
if (errCode != 0) {
|
||||
// we got an error!
|
||||
let errs = [];
|
||||
for (const errKey of Object.keys(encoderErrors)) {
|
||||
if (errCode & errKey) {
|
||||
errs.push(encoderErrors[errKey]);
|
||||
}
|
||||
}
|
||||
retMsg = errs.join(', ');
|
||||
}
|
||||
|
||||
return retMsg;
|
||||
return this.getErrorString(errCode, 'ENCODER_ERROR');
|
||||
},
|
||||
controllerErrorMsg() {
|
||||
let retMsg = "none";
|
||||
let errCode = this.controllerErr;
|
||||
|
||||
if (errCode != 0) {
|
||||
// we got an error!
|
||||
let errs = [];
|
||||
for (const errKey of Object.keys(controllerErrors)) {
|
||||
if (errCode & errKey) {
|
||||
errs.push(controllerErrors[errKey]);
|
||||
}
|
||||
}
|
||||
retMsg = errs.join(', ');
|
||||
}
|
||||
|
||||
return retMsg;
|
||||
return this.getErrorString(errCode, 'CONTROLLER_ERROR');
|
||||
},
|
||||
axisError() {
|
||||
let errCode = this.axisErr;
|
||||
@@ -226,27 +138,33 @@ export default {
|
||||
return errCode != 0;
|
||||
},
|
||||
error() {
|
||||
return this.axisError || this.motorError || this.encoderError || this.controllerError;
|
||||
return (
|
||||
this.axisError ||
|
||||
this.motorError ||
|
||||
this.encoderError ||
|
||||
this.controllerError
|
||||
);
|
||||
},
|
||||
},
|
||||
created() {
|
||||
// set up timeout loop for grabbing axis error values
|
||||
let update = () => {
|
||||
// Do we have an active connection to the ODrive that contains this axis?
|
||||
if (this.$store.state.ODrivesConnected[this.axis.split('.')[0]]) {
|
||||
if (this.$store.state.ODrivesConnected[this.axis.split(".")[0]]) {
|
||||
fetchParam(this.axis + ".error");
|
||||
fetchParam(this.axis + '.motor.error');
|
||||
fetchParam(this.axis + '.controller.error');
|
||||
fetchParam(this.axis + '.encoder.error');
|
||||
this.axisErr = getVal(this.axis + '.error');
|
||||
this.motorErr = getVal(this.axis + '.motor.error');
|
||||
this.controllerErr = getVal(this.axis + '.controller.error');
|
||||
this.encoderErr = getVal(this.axis + '.encoder.error');
|
||||
fetchParam(this.axis + ".motor.error");
|
||||
fetchParam(this.axis + ".controller.error");
|
||||
fetchParam(this.axis + ".encoder.error");
|
||||
this.axisErr = getVal(this.axis + ".error");
|
||||
this.motorErr = getVal(this.axis + ".motor.error");
|
||||
this.controllerErr = getVal(this.axis + ".controller.error");
|
||||
this.encoderErr = getVal(this.axis + ".encoder.error");
|
||||
}
|
||||
// ODrive not connected
|
||||
setTimeout(update, 1000);
|
||||
}
|
||||
update();
|
||||
};
|
||||
this.cyclicUpdate = setInterval(update, 1000);
|
||||
},
|
||||
beforeDestroy() {
|
||||
clearInterval(this.cyclicUpdate);
|
||||
}
|
||||
};
|
||||
</script>
|
||||
|
||||
@@ -3,7 +3,7 @@
|
||||
<button class="close-button" @click=deleteAction>X</button>
|
||||
<span class="ctrlName">{{shortPath}}:</span>
|
||||
<div class="right">
|
||||
<input v-on:change="newVal" :placeholder="initVal" :value="this.value"/>
|
||||
<input v-on:change="newVal" :placeholder="initVal" :value="valueDisplay" spellcheck="false"/>
|
||||
<button class="action-button close-button" @click="putVal">Send</button>
|
||||
</div>
|
||||
</div>
|
||||
@@ -11,6 +11,7 @@
|
||||
|
||||
<script>
|
||||
import { putVal, parseMath } from "../../lib/odrive_utils.js";
|
||||
import { numberDisplay } from "../../lib/utils.js"
|
||||
|
||||
export default {
|
||||
name: "Action",
|
||||
@@ -35,6 +36,9 @@ export default {
|
||||
let keys = this.path.split('.');
|
||||
keys.shift();
|
||||
return keys.join('.');
|
||||
},
|
||||
valueDisplay() {
|
||||
return numberDisplay(this.value);
|
||||
}
|
||||
},
|
||||
methods: {
|
||||
|
||||
@@ -4,7 +4,7 @@
|
||||
<span class="ctrlName">{{name}}:</span>
|
||||
<div class="right">
|
||||
<span v-if="!writeAccess" class="ctrlVal">{{value}}</span>
|
||||
<input v-if="writeAccess" :placeholder="value" v-on:change="putVal" :value="value"/>
|
||||
<input v-if="writeAccess" :placeholder="value" v-on:change="putVal" :value="value" spellcheck="false"/>
|
||||
<!-- <span class="unit">[{{unit}}]</span> -->
|
||||
</div>
|
||||
</div>
|
||||
@@ -12,6 +12,7 @@
|
||||
|
||||
<script>
|
||||
import { getVal, getReadonly, putVal, fetchParam, getUnit, parseMath } from "../../lib/odrive_utils.js";
|
||||
import { numberDisplay } from "../../lib/utils.js";
|
||||
|
||||
export default {
|
||||
name: "CtrlNumeric",
|
||||
@@ -25,7 +26,9 @@ export default {
|
||||
value: function () {
|
||||
let keys = this.path.split('.');
|
||||
keys.shift();
|
||||
return parseFloat(getVal(keys.join('.'))).toFixed(3);
|
||||
let val = getVal(keys.join('.'));
|
||||
console.log(val + ' ' + typeof val);
|
||||
return numberDisplay(val);
|
||||
},
|
||||
name: function () {
|
||||
let keys = this.path.split(".");
|
||||
|
||||
@@ -5,10 +5,10 @@
|
||||
<span class="ctrlName">{{name}}</span>
|
||||
</div>
|
||||
<div class="slider-container">
|
||||
<input type="number" :value="min" v-on:change="setMin"/>
|
||||
<input :value="displayMin" :placeholder="displayMin" v-on:change="setMin"/>
|
||||
<!-- <vue-slider v-model="value" :min="min" :max="max" :interval="interval" /> -->
|
||||
<vue-slider v-model="value" :data="data" @change="putVal"/>
|
||||
<input type="number" :value="max" v-on:change="setMax" />
|
||||
<vue-slider v-model="value" :data="data" :adsorb="true" @change="putVal"/>
|
||||
<input :value="displayMax" :placeholder="displayMax" v-on:change="setMax" />
|
||||
</div>
|
||||
</div>
|
||||
</template>
|
||||
@@ -16,7 +16,8 @@
|
||||
<script>
|
||||
import VueSlider from "vue-slider-component";
|
||||
import "vue-slider-component/theme/default.css";
|
||||
import { getVal, putVal } from "../../lib/odrive_utils.js";
|
||||
import { getVal, putVal, parseMath } from "../../lib/odrive_utils.js";
|
||||
import { numberDisplay } from "../../lib/utils.js";
|
||||
|
||||
export default {
|
||||
name: "CtrlSlider",
|
||||
@@ -49,6 +50,12 @@ export default {
|
||||
sliderData: function () {
|
||||
let interval = (this.max - this.min) / 100;
|
||||
return Array.from(Array(101), (_, i) => this.min + interval * i);
|
||||
},
|
||||
displayMin() {
|
||||
return numberDisplay(this.min);
|
||||
},
|
||||
displayMax() {
|
||||
return numberDisplay(this.max);
|
||||
}
|
||||
},
|
||||
methods: {
|
||||
@@ -59,27 +66,47 @@ export default {
|
||||
putVal(keys.join('.'), value);
|
||||
},
|
||||
setMin: function (e) {
|
||||
this.min = parseFloat(e.target.value);
|
||||
this.data = Array.from(Array(101), (_, i) => this.min + (this.max-this.min) / 100 * i);
|
||||
let min = parseMath(e.target.value);
|
||||
if (min < this.max) {
|
||||
this.min = min;
|
||||
this.data = Array.from(Array(101), (_, i) => this.min + (this.max-this.min) / 100 * i);
|
||||
this.value = this.findNearest(this.data, this.value);
|
||||
}
|
||||
},
|
||||
setMax: function (e) {
|
||||
this.max = parseFloat(e.target.value);
|
||||
this.data = Array.from(Array(101), (_, i) => this.min + (this.max-this.min) / 100 * i);
|
||||
let max = parseMath(e.target.value);
|
||||
if (max > this.min) {
|
||||
this.max = max;
|
||||
this.data = Array.from(Array(101), (_, i) => this.min + (this.max-this.min) / 100 * i);
|
||||
this.value = this.findNearest(this.data, this.value);
|
||||
}
|
||||
},
|
||||
deleteCtrl: function() {
|
||||
// commit a mutation in the store with the relevant information
|
||||
this.$store.commit("removeCtrlFromDash", {dashID: this.dashID, path: this.path});
|
||||
},
|
||||
findNearest(data, value) {
|
||||
// find item in data closest to value
|
||||
let diff = Number.POSITIVE_INFINITY;
|
||||
let retVal = value;
|
||||
for (const val of data) {
|
||||
if (Math.abs(val - value) < diff) {
|
||||
diff = Math.abs(val - value);
|
||||
retVal = val;
|
||||
}
|
||||
}
|
||||
return retVal;
|
||||
}
|
||||
},
|
||||
mounted() {
|
||||
let initVal = () => {
|
||||
let keys = this.path.split(".");
|
||||
keys.shift(); // don't need first key here
|
||||
return getVal(keys.join('.'));
|
||||
return parseFloat(getVal(keys.join('.')));
|
||||
};
|
||||
this.value = initVal();
|
||||
this.max = parseFloat((this.value * 4).toFixed(3));
|
||||
this.min = parseFloat((this.value / 4).toFixed(3));
|
||||
this.max = this.value * 4;
|
||||
this.min = this.value / 4;
|
||||
this.data = Array.from(Array(101), (_, i) => this.min + (this.max-this.min) / 100 * i);
|
||||
},
|
||||
};
|
||||
|
||||
@@ -51,8 +51,10 @@ export default {
|
||||
mounted() {
|
||||
this.timeStart = Date.now();
|
||||
//this.initData(); //set label for dataset and color
|
||||
this.fillData();
|
||||
this.liveData();
|
||||
this.cyclicUpdate = setInterval(() => this.fillData(), 50);
|
||||
},
|
||||
beforeDestroy() {
|
||||
clearInterval(this.cyclicUpdate);
|
||||
},
|
||||
methods: {
|
||||
fillData() {
|
||||
@@ -85,15 +87,6 @@ export default {
|
||||
],
|
||||
};
|
||||
},
|
||||
liveData() {
|
||||
setTimeout(() => {
|
||||
this.liveData();
|
||||
}, 50);
|
||||
//if (this.$store.state.sampling == true) {
|
||||
// this.fillData();
|
||||
//}
|
||||
this.fillData();
|
||||
},
|
||||
deletePlot: function () {
|
||||
// commit a mutation in the store with the relevant information
|
||||
this.$store.commit("removePlotFromDash", {
|
||||
|
||||
@@ -42,13 +42,13 @@ export function fetchParam(path) {
|
||||
|
||||
export function parseMath(inString) {
|
||||
// given an input string that is valid arithmetic, use eval() to evaluate it
|
||||
let allowedChars = "0123456789eE/*-+.()";
|
||||
//let allowedChars = "0123456789eE/*-+.()";
|
||||
let send = true;
|
||||
for (const c of inString) {
|
||||
if (!allowedChars.includes(c)) {
|
||||
send = false;
|
||||
}
|
||||
}
|
||||
//for (const c of inString) {
|
||||
// if (!allowedChars.includes(c)) {
|
||||
// send = false;
|
||||
// }
|
||||
//}
|
||||
if (send) {
|
||||
return eval(inString);
|
||||
}
|
||||
@@ -60,6 +60,12 @@ export function parseMath(inString) {
|
||||
export function putVal(path, value) {
|
||||
console.log("path: " + path + ", val: " + value + ", type: " + typeof value);
|
||||
if (store.state.ODrivesConnected[path.split('.')[0]]) {
|
||||
if (value == Number.POSITIVE_INFINITY) {
|
||||
value = "Infinity";
|
||||
}
|
||||
else if (value == Number.NEGATIVE_INFINITY) {
|
||||
value = "-Infinity";
|
||||
}
|
||||
socketio.sendEvent({
|
||||
type: "setProperty",
|
||||
data: {path: path, val: value, type: typeof value}
|
||||
@@ -120,9 +126,6 @@ export async function motorCalibration(odrive, axis) {
|
||||
|
||||
state = getVal(odrive + axis + ".current_state");
|
||||
motorError = getVal(odrive + axis + ".motor.error");
|
||||
if (run) {
|
||||
setTimeout(updateVals, 100);
|
||||
}
|
||||
}
|
||||
|
||||
// set up our state watch function
|
||||
@@ -137,8 +140,7 @@ export async function motorCalibration(odrive, axis) {
|
||||
}
|
||||
|
||||
// start getting live updates
|
||||
let run = true;
|
||||
updateVals();
|
||||
let cylicUpdate = setInterval(updateVals, 100);
|
||||
|
||||
// send motor calibration command to correct odrive and axis
|
||||
putVal(odrive + axis + ".requested_state", odriveEnums.AXIS_STATE_MOTOR_CALIBRATION);
|
||||
@@ -150,7 +152,7 @@ export async function motorCalibration(odrive, axis) {
|
||||
const result = await waitFor(end);
|
||||
|
||||
// stop our parameter updates
|
||||
run = false;
|
||||
clearInterval(cylicUpdate);
|
||||
|
||||
return result;
|
||||
}
|
||||
@@ -167,9 +169,6 @@ export async function encoderCalibration(odrive,axis) {
|
||||
|
||||
state = getVal(odrive + axis + ".current_state");
|
||||
encoderError = getVal(odrive + axis + ".encoder.error");
|
||||
if (run) {
|
||||
setTimeout(updateVals, 100);
|
||||
}
|
||||
}
|
||||
|
||||
// set up our state watch function
|
||||
@@ -184,8 +183,7 @@ export async function encoderCalibration(odrive,axis) {
|
||||
}
|
||||
|
||||
// start getting live updates
|
||||
let run = true;
|
||||
updateVals();
|
||||
let cylicUpdate = setInterval(updateVals, 100);
|
||||
|
||||
// start encoder offset cal
|
||||
putVal(odrive + axis + ".requested_state", odriveEnums.AXIS_STATE_ENCODER_OFFSET_CALIBRATION);
|
||||
@@ -197,7 +195,7 @@ export async function encoderCalibration(odrive,axis) {
|
||||
const result = await waitFor(end);
|
||||
|
||||
// stop our parameter updates
|
||||
run = false;
|
||||
clearInterval(cylicUpdate);
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
@@ -55,4 +55,39 @@ export let wait = (time) => {
|
||||
return new Promise(resolve => {
|
||||
setTimeout(() => resolve(), time);
|
||||
});
|
||||
}
|
||||
|
||||
export let pathsFromTree = (tree) => {
|
||||
let flatpaths = [];
|
||||
let path = [];
|
||||
let pathFromTree = (tree) => {
|
||||
for (const key of Object.keys(tree)) {
|
||||
path.push(key);
|
||||
if (tree[key] != null && typeof tree[key] == "object") {
|
||||
pathFromTree(tree[key]);
|
||||
}
|
||||
else {
|
||||
flatpaths.push(path.join('.'));
|
||||
}
|
||||
path.pop();
|
||||
}
|
||||
}
|
||||
// array path
|
||||
pathFromTree(tree);
|
||||
return flatpaths;
|
||||
}
|
||||
|
||||
export let numberDisplay = (val) => {
|
||||
// if a number can be represented with 3 decimals, return it in that form
|
||||
// otherwise, return scientific notation
|
||||
let retVal = '';
|
||||
try {
|
||||
retVal = parseFloat(val).toFixed(3);
|
||||
if (retVal == '0.000' && val != 0 || retVal.length > 7) {
|
||||
retVal = parseFloat(val).toExponential(3);
|
||||
}
|
||||
} catch (error) {
|
||||
console.log(error);
|
||||
}
|
||||
return retVal;
|
||||
}
|
||||
@@ -120,7 +120,15 @@ export default new Vuex.Store({
|
||||
}
|
||||
return ref;
|
||||
};
|
||||
Vue.set(createNestedObject(state.odrives, payload.path), "val", payload.val);
|
||||
let val = payload.val
|
||||
if (val == "Infinity") {
|
||||
val = Number.POSITIVE_INFINITY;
|
||||
console.log("val is infinity");
|
||||
}
|
||||
else if (val == "-Infinity") {
|
||||
val = Number.NEGATIVE_INFINITY;
|
||||
}
|
||||
Vue.set(createNestedObject(state.odrives, payload.path), "val", val);
|
||||
|
||||
},
|
||||
addSampledProperty(state, path) {
|
||||
@@ -244,6 +252,18 @@ export default new Vuex.Store({
|
||||
if (Object.prototype.hasOwnProperty.call(odriveObj[key], "val")) {
|
||||
// parse from string to a type that we care about
|
||||
switch (odriveObj[key]["type"]) {
|
||||
case "str": {
|
||||
// for handling infinity
|
||||
let val;
|
||||
if (odriveObj[key]["val"] == 'Infinity') {
|
||||
val = Number.POSITIVE_INFINITY;
|
||||
}
|
||||
else if (odriveObj[key]["val"] == '-Infinity') {
|
||||
val = Number.NEGATIVE_INFINITY;
|
||||
}
|
||||
retObj[key] = val;
|
||||
break;
|
||||
}
|
||||
case "float":
|
||||
retObj[key] = parseFloat(parseFloat(odriveObj[key]["val"]).toFixed(3));
|
||||
break;
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user