Skip to content

Commit

Permalink
Merge pull request #284 from tinymovr/studio/argument_input_dialog
Browse files Browse the repository at this point in the history
Add dialog for inputting function arguments
  • Loading branch information
yconst authored Sep 5, 2023
2 parents b4653b6 + 41cafb2 commit c746b82
Show file tree
Hide file tree
Showing 37 changed files with 350 additions and 333 deletions.
163 changes: 72 additions & 91 deletions docs/protocol/reference.rst

Large diffs are not rendered by default.

Binary file modified firmware/bootloader/bootloader_M51.bin
Binary file not shown.
Binary file modified firmware/bootloader/bootloader_R32.bin
Binary file not shown.
Binary file modified firmware/bootloader/bootloader_R33.bin
Binary file not shown.
Binary file modified firmware/bootloader/bootloader_R50.bin
Binary file not shown.
Binary file modified firmware/bootloader/bootloader_R51.bin
Binary file not shown.
Binary file modified firmware/bootloader/bootloader_R52.bin
Binary file not shown.
2 changes: 1 addition & 1 deletion firmware/src/can/can.c
Original file line number Diff line number Diff line change
Expand Up @@ -161,7 +161,7 @@ void CAN_restore_config(CANConfig *config_)
config = *config_;
}

void CAN_task(void) {
void CAN_update(void) {
// Transmit heartbeat
const uint32_t msg_diff = msTicks - state.last_msg_ms;
if (msg_diff >= config.heartbeat_period && PAC55XX_CAN->SR.TBS != 0)
Expand Down
2 changes: 1 addition & 1 deletion firmware/src/can/can.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,4 +40,4 @@ void CAN_process_interrupt(void);
CANConfig *CAN_get_config(void);
void CAN_restore_config(CANConfig *config_);

void CAN_task(void);
void CAN_update(void);
34 changes: 5 additions & 29 deletions firmware/src/can/can_endpoints.c
Original file line number Diff line number Diff line change
Expand Up @@ -18,8 +18,8 @@
#include <src/can/can_endpoints.h>


uint8_t (*avlos_endpoints[81])(uint8_t * buffer, uint8_t * buffer_len, Avlos_Command cmd) = {&avlos_protocol_hash, &avlos_uid, &avlos_fw_version, &avlos_hw_revision, &avlos_Vbus, &avlos_Ibus, &avlos_power, &avlos_temp, &avlos_calibrated, &avlos_errors, &avlos_save_config, &avlos_erase_config, &avlos_reset, &avlos_invoke_bootloader, &avlos_scheduler_total, &avlos_scheduler_busy, &avlos_scheduler_errors, &avlos_controller_state, &avlos_controller_mode, &avlos_controller_warnings, &avlos_controller_errors, &avlos_controller_position_setpoint, &avlos_controller_position_p_gain, &avlos_controller_velocity_setpoint, &avlos_controller_velocity_limit, &avlos_controller_velocity_p_gain, &avlos_controller_velocity_i_gain, &avlos_controller_velocity_deadband, &avlos_controller_velocity_increment, &avlos_controller_current_Iq_setpoint, &avlos_controller_current_Id_setpoint, &avlos_controller_current_Iq_limit, &avlos_controller_current_Iq_estimate, &avlos_controller_current_bandwidth, &avlos_controller_current_Iq_p_gain, &avlos_controller_current_max_Ibus_regen, &avlos_controller_current_max_Ibrake, &avlos_controller_voltage_Vq_setpoint, &avlos_controller_calibrate, &avlos_controller_idle, &avlos_controller_position_mode, &avlos_controller_velocity_mode, &avlos_controller_current_mode, &avlos_controller_set_pos_vel_setpoints, &avlos_comms_can_rate, &avlos_comms_can_id, &avlos_motor_R, &avlos_motor_L, &avlos_motor_pole_pairs, &avlos_motor_type, &avlos_motor_offset, &avlos_motor_direction, &avlos_motor_calibrated, &avlos_motor_I_cal, &avlos_motor_errors, &avlos_encoder_position_estimate, &avlos_encoder_velocity_estimate, &avlos_encoder_type, &avlos_encoder_bandwidth, &avlos_encoder_calibrated, &avlos_encoder_errors, &avlos_traj_planner_max_accel, &avlos_traj_planner_max_decel, &avlos_traj_planner_max_vel, &avlos_traj_planner_t_accel, &avlos_traj_planner_t_decel, &avlos_traj_planner_t_total, &avlos_traj_planner_move_to, &avlos_traj_planner_move_to_tlimit, &avlos_traj_planner_errors, &avlos_homing_velocity, &avlos_homing_max_homing_t, &avlos_homing_retract_dist, &avlos_homing_warnings, &avlos_homing_stall_detect_velocity, &avlos_homing_stall_detect_delta_pos, &avlos_homing_stall_detect_t, &avlos_homing_home, &avlos_watchdog_enabled, &avlos_watchdog_triggered, &avlos_watchdog_timeout };
uint32_t avlos_proto_hash = 4244018107;
uint8_t (*avlos_endpoints[79])(uint8_t * buffer, uint8_t * buffer_len, Avlos_Command cmd) = {&avlos_protocol_hash, &avlos_uid, &avlos_fw_version, &avlos_hw_revision, &avlos_Vbus, &avlos_Ibus, &avlos_power, &avlos_temp, &avlos_calibrated, &avlos_errors, &avlos_save_config, &avlos_erase_config, &avlos_reset, &avlos_enter_dfu, &avlos_scheduler_errors, &avlos_controller_state, &avlos_controller_mode, &avlos_controller_warnings, &avlos_controller_errors, &avlos_controller_position_setpoint, &avlos_controller_position_p_gain, &avlos_controller_velocity_setpoint, &avlos_controller_velocity_limit, &avlos_controller_velocity_p_gain, &avlos_controller_velocity_i_gain, &avlos_controller_velocity_deadband, &avlos_controller_velocity_increment, &avlos_controller_current_Iq_setpoint, &avlos_controller_current_Id_setpoint, &avlos_controller_current_Iq_limit, &avlos_controller_current_Iq_estimate, &avlos_controller_current_bandwidth, &avlos_controller_current_Iq_p_gain, &avlos_controller_current_max_Ibus_regen, &avlos_controller_current_max_Ibrake, &avlos_controller_voltage_Vq_setpoint, &avlos_controller_calibrate, &avlos_controller_idle, &avlos_controller_position_mode, &avlos_controller_velocity_mode, &avlos_controller_current_mode, &avlos_controller_set_pos_vel_setpoints, &avlos_comms_can_rate, &avlos_comms_can_id, &avlos_motor_R, &avlos_motor_L, &avlos_motor_pole_pairs, &avlos_motor_type, &avlos_motor_offset, &avlos_motor_direction, &avlos_motor_calibrated, &avlos_motor_I_cal, &avlos_motor_errors, &avlos_encoder_position_estimate, &avlos_encoder_velocity_estimate, &avlos_encoder_type, &avlos_encoder_bandwidth, &avlos_encoder_calibrated, &avlos_encoder_errors, &avlos_traj_planner_max_accel, &avlos_traj_planner_max_decel, &avlos_traj_planner_max_vel, &avlos_traj_planner_t_accel, &avlos_traj_planner_t_decel, &avlos_traj_planner_t_total, &avlos_traj_planner_move_to, &avlos_traj_planner_move_to_tlimit, &avlos_traj_planner_errors, &avlos_homing_velocity, &avlos_homing_max_homing_t, &avlos_homing_retract_dist, &avlos_homing_warnings, &avlos_homing_stall_detect_velocity, &avlos_homing_stall_detect_delta_pos, &avlos_homing_stall_detect_t, &avlos_homing_home, &avlos_watchdog_enabled, &avlos_watchdog_triggered, &avlos_watchdog_timeout };
uint32_t avlos_proto_hash = 4118115615;

uint32_t _avlos_get_proto_hash(void)
{
Expand Down Expand Up @@ -164,42 +164,18 @@ uint8_t avlos_reset(uint8_t * buffer, uint8_t * buffer_len, Avlos_Command cmd)
return AVLOS_RET_CALL;
}

uint8_t avlos_invoke_bootloader(uint8_t * buffer, uint8_t * buffer_len, Avlos_Command cmd)
uint8_t avlos_enter_dfu(uint8_t * buffer, uint8_t * buffer_len, Avlos_Command cmd)
{
system_invoke_bootloader();
system_enter_dfu();

return AVLOS_RET_CALL;
}

uint8_t avlos_scheduler_total(uint8_t * buffer, uint8_t * buffer_len, Avlos_Command cmd)
{
if (AVLOS_CMD_READ == cmd) {
uint32_t v;
v = Scheduler_GetTotalCycles();
*buffer_len = sizeof(v);
memcpy(buffer, &v, sizeof(v));
return AVLOS_RET_READ;
}
return AVLOS_RET_NOACTION;
}

uint8_t avlos_scheduler_busy(uint8_t * buffer, uint8_t * buffer_len, Avlos_Command cmd)
{
if (AVLOS_CMD_READ == cmd) {
uint32_t v;
v = Scheduler_GetBusyCycles();
*buffer_len = sizeof(v);
memcpy(buffer, &v, sizeof(v));
return AVLOS_RET_READ;
}
return AVLOS_RET_NOACTION;
}

uint8_t avlos_scheduler_errors(uint8_t * buffer, uint8_t * buffer_len, Avlos_Command cmd)
{
if (AVLOS_CMD_READ == cmd) {
uint8_t v;
v = controller_get_errors();
v = scheduler_get_errors();
*buffer_len = sizeof(v);
memcpy(buffer, &v, sizeof(v));
return AVLOS_RET_READ;
Expand Down
35 changes: 10 additions & 25 deletions firmware/src/can/can_endpoints.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,12 @@ typedef enum
{
ERRORS_NONE = 0,
ERRORS_UNDERVOLTAGE = (1 << 0),
ERRORS_DRIVER_FAULT = (1 << 1)
ERRORS_DRIVER_FAULT = (1 << 1),
ERRORS_CHARGE_PUMP_FAULT_STAT = (1 << 2),
ERRORS_CHARGE_PUMP_FAULT = (1 << 3),
ERRORS_DRV10_DISABLE = (1 << 4),
ERRORS_DRV32_DISABLE = (1 << 5),
ERRORS_DRV54_DISABLE = (1 << 6)
} errors_flags;

typedef enum
Expand Down Expand Up @@ -91,7 +96,7 @@ typedef enum
} encoder_type_options;

extern uint32_t avlos_proto_hash;
extern uint8_t (*avlos_endpoints[81])(uint8_t * buffer, uint8_t * buffer_len, Avlos_Command cmd);
extern uint8_t (*avlos_endpoints[79])(uint8_t * buffer, uint8_t * buffer_len, Avlos_Command cmd);
extern uint32_t _avlos_get_proto_hash(void);

/*
Expand Down Expand Up @@ -225,34 +230,14 @@ uint8_t avlos_erase_config(uint8_t * buffer, uint8_t * buffer_len, Avlos_Command
uint8_t avlos_reset(uint8_t * buffer, uint8_t * buffer_len, Avlos_Command cmd);

/*
* avlos_invoke_bootloader
* avlos_enter_dfu
*
* Invoke the bootloader.
* Enter DFU mode.
*
* @param buffer
* @param buffer_len
*/
uint8_t avlos_invoke_bootloader(uint8_t * buffer, uint8_t * buffer_len, Avlos_Command cmd);

/*
* avlos_scheduler_total
*
* Total processor cycles in a single PWM cycle.
*
* @param buffer
* @param buffer_len
*/
uint8_t avlos_scheduler_total(uint8_t * buffer, uint8_t * buffer_len, Avlos_Command cmd);

/*
* avlos_scheduler_busy
*
* Busy processor cycles in a single PWM cycle.
*
* @param buffer
* @param buffer_len
*/
uint8_t avlos_scheduler_busy(uint8_t * buffer, uint8_t * buffer_len, Avlos_Command cmd);
uint8_t avlos_enter_dfu(uint8_t * buffer, uint8_t * buffer_len, Avlos_Command cmd);

/*
* avlos_scheduler_errors
Expand Down
3 changes: 2 additions & 1 deletion firmware/src/config.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,9 @@
// Timer clock divider
#define TXCTL_PS_DIV TXCTL_PS_DIV2

// Desired PWM Frequency (Hz).
// PWM and Systick frequency
#define PWM_FREQ_HZ (20000)
#define SYSTICK_FREQ_HZ (1000)

// Control parameters
#define PWM_LIMIT (0.8f)
Expand Down
4 changes: 2 additions & 2 deletions firmware/src/controller/controller.c
Original file line number Diff line number Diff line change
Expand Up @@ -124,11 +124,11 @@ void Controller_ControlLoop(void)
reset_calibration();
if (ENCODER_MA7XX == encoder_get_type())
{
(void)((CalibrateResistance() && CalibrateInductance()) && CalibrateDirectionAndPolePairs() && calibrate_offset_and_rectification());
(void)((CalibrateADCOffset() && CalibrateResistance() && CalibrateInductance()) && CalibrateDirectionAndPolePairs() && calibrate_offset_and_rectification());
}
else if (ENCODER_HALL == encoder_get_type())
{
(void)((CalibrateResistance() && CalibrateInductance()) && calibrate_hall_sequence());
(void)((CalibrateADCOffset() && CalibrateResistance() && CalibrateInductance()) && calibrate_hall_sequence());
}
state.is_calibrating = false;
controller_set_state(STATE_IDLE);
Expand Down
11 changes: 1 addition & 10 deletions firmware/src/gatedriver/gatedriver.c
Original file line number Diff line number Diff line change
Expand Up @@ -19,13 +19,6 @@
#include <src/motor/motor.h>
#include <src/gatedriver/gatedriver.h>

struct GateDriver_ gateDriver =
{
.state = GATEDRIVER_DISABLED
};

void GateDriver_Init(void) {}

TM_RAMFUNC void gate_driver_enable(void)
{
// Select PWMA peripheral for Port B
Expand All @@ -47,7 +40,6 @@ TM_RAMFUNC void gate_driver_enable(void)

pac5xxx_tile_register_write(ADDR_CFGDRV4,
pac5xxx_tile_register_read(ADDR_CFGDRV4) | 0x1); // BBM is bit 0
gateDriver.state = GATEDRIVER_ENABLED;
}

TM_RAMFUNC void gate_driver_disable(void)
Expand All @@ -66,12 +58,11 @@ TM_RAMFUNC void gate_driver_disable(void)

// Turn on output enables
PAC55XX_GPIOB->OUTMASK.w = 0x00;
gateDriver.state = GATEDRIVER_DISABLED;
}

TM_RAMFUNC bool gate_driver_is_enabled(void)
{
return (GATEDRIVER_ENABLED == gateDriver.state);
return ((pac5xxx_tile_register_read(ADDR_ENDRV) & 0x1) == 1);
}

TM_RAMFUNC void gate_driver_set_duty_cycle(const FloatTriplet *dutycycles)
Expand Down
10 changes: 0 additions & 10 deletions firmware/src/gatedriver/gatedriver.h
Original file line number Diff line number Diff line change
Expand Up @@ -18,17 +18,7 @@
#ifndef GATEDRIVER_GATEDRIVER_H_
#define GATEDRIVER_GATEDRIVER_H_

typedef enum {
GATEDRIVER_DISABLED = 0,
GATEDRIVER_ENABLED = 1
} GateDriverState;

struct GateDriver_
{
GateDriverState state;
};

void GateDriver_Init(void);
void gate_driver_enable(void);
void gate_driver_disable(void);
bool gate_driver_is_enabled(void);
Expand Down
1 change: 0 additions & 1 deletion firmware/src/main.c
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,6 @@ int main(void)
UART_Init();
observer_init();
ADC_Init();
GateDriver_Init();
CAN_init();
Timer_Init();
Watchdog_init();
Expand Down
8 changes: 8 additions & 0 deletions firmware/src/motor/calibration.c
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,14 @@
static inline void set_epos_and_wait(float angle, float I_setpoint);
static inline void wait_a_while(void);

bool CalibrateADCOffset(void)
{
// We only need to wait here, the ADC loop will
// perform the offset calibration automatically
wait_a_while();
return true;
}

bool CalibrateResistance(void)
{
if (!motor_get_is_gimbal())
Expand Down
1 change: 1 addition & 0 deletions firmware/src/motor/calibration.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@
#define CAL_V_INDUCTANCE (5.0f)
#endif

bool CalibrateADCOffset(void);
bool CalibrateResistance(void);
bool CalibrateInductance(void);
bool CalibrateDirectionAndPolePairs(void);
Expand Down
21 changes: 3 additions & 18 deletions firmware/src/scheduler/scheduler.c
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,6 @@ void WaitForControlLoopInterrupt(void)
else
{
state.busy = false;
state.busy_cycles = DWT->CYCCNT - state.busy_loop_start;
// Go back to sleep
__DSB();
__ISB();
Expand All @@ -72,15 +71,14 @@ void WaitForControlLoopInterrupt(void)
}
state.busy = true;
state.adc_interrupt = false;
state.busy_loop_start = DWT->CYCCNT;
// We have to service the control loop by updating
// current measurements and encoder estimates.
if (ENCODER_MA7XX == encoder_get_type())
{
ma7xx_send_angle_cmd();
}
ADC_update();
system_update();

encoder_update(true);
observer_update();
// At this point control is returned to main loop.
Expand All @@ -103,10 +101,6 @@ void ADC_IRQHandler(void)
{
state.adc_interrupt = true;
}

const uint32_t current_timestamp = DWT->CYCCNT;
state.total_cycles = current_timestamp - state.total_loop_start;
state.total_loop_start = current_timestamp;
}

void CAN_IRQHandler(void)
Expand All @@ -118,7 +112,8 @@ void CAN_IRQHandler(void)
void SysTick_Handler(void)
{
msTicks = msTicks + 1;
CAN_task();
CAN_update();
system_update();
}

void UART_ReceiveMessageHandler(void)
Expand All @@ -134,16 +129,6 @@ void Wdt_IRQHandler(void)
PAC55XX_WWDT->WWDTFLAG.IF = 1;
}

TM_RAMFUNC uint32_t Scheduler_GetTotalCycles(void)
{
return state.total_cycles;
}

TM_RAMFUNC uint32_t Scheduler_GetBusyCycles(void)
{
return state.busy_cycles;
}

TM_RAMFUNC uint8_t scheduler_get_errors(void)
{
return state.errors;
Expand Down
7 changes: 0 additions & 7 deletions firmware/src/scheduler/scheduler.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,15 +26,8 @@ typedef struct
bool busy;

uint8_t errors;
uint32_t busy_cycles;
uint32_t total_cycles;
uint32_t busy_loop_start;
uint32_t total_loop_start;
} SchedulerState;

void WaitForControlLoopInterrupt(void);

uint32_t Scheduler_GetTotalCycles(void);
uint32_t Scheduler_GetBusyCycles(void);

uint8_t scheduler_get_errors(void);
23 changes: 15 additions & 8 deletions firmware/src/system/system.c
Original file line number Diff line number Diff line change
Expand Up @@ -82,22 +82,17 @@ void system_init(void)
// Vp = 10V , 440mA-540mA, Charge Pump Enable
pac5xxx_tile_register_write(ADDR_SYSCONF, 0x01);

// Ensure ADC GP0 register is zero, to bypass bootloader on next boot
// Ensure ADC GP0 register is zero, to bypass DFU mode on next boot
pac5xxx_tile_register_write(ADDR_GP0, 0);

// Configure reporting of mcu cycles
CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk;
DWT->CYCCNT = 0;
DWT->CTRL |= DWT_CTRL_CYCCNTENA_Msk;

// Configure error handling
SCB->CCR |= 0x10;

// Arbitrary value to avoid division by zero
state.Vbus = 12.0f;

// Derive VBus D value for given tau value
config.Vbus_D = 1.0f - powf(EPSILON, -1.0f / (config.Vbus_tau * PWM_FREQ_HZ));
config.Vbus_D = 1.0f - powf(EPSILON, -1.0f / (config.Vbus_tau * SYSTICK_FREQ_HZ));

/* Initialize Systick per 1ms */
SysTick_Config(150000); // TODO: Use var
Expand All @@ -110,6 +105,18 @@ TM_RAMFUNC void system_update(void)
{
state.errors |= ERRORS_UNDERVOLTAGE;
}
const uint8_t drv_status = pac5xxx_tile_register_read(ADDR_STATDRV);
if (drv_status > 0)
{
state.errors |= ((drv_status & 0x7) << 4);
}
const uint8_t drv_fault = pac5xxx_tile_register_read(ADDR_DRV_FLT);
if (drv_fault > 0)
{
// We use 0x5 mask because we ignore CHARGE_PUMP_FAULT_STAT
// for the time being, as it seems to always be set.
state.errors |= ((drv_fault & 0x5) << 1);
}
}

void system_reset(void)
Expand All @@ -118,7 +125,7 @@ void system_reset(void)
NVIC_SystemReset();
}

void system_invoke_bootloader(void)
void system_enter_dfu(void)
{
pac5xxx_tile_register_write(ADDR_GP0, BTL_TRIGGER_PATTERN);
NVIC_SystemReset();
Expand Down
2 changes: 1 addition & 1 deletion firmware/src/system/system.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ typedef struct {
void system_init(void);
void system_update(void);
void system_reset(void);
void system_invoke_bootloader(void);
void system_enter_dfu(void);

inline uint8_t system_get_fw_version_string(char *buffer)
{
Expand Down
3 changes: 2 additions & 1 deletion studio/Python/Manifest.in
Original file line number Diff line number Diff line change
Expand Up @@ -7,4 +7,5 @@ include tinymovr/resources/icons/empty.png
include tinymovr/resources/icons/empty@2x.png
include tinymovr/resources/icons/empty_dark.png
include tinymovr/resources/icons/empty_dark@2x.png
include tinymovr/config/device.yaml
include tinymovr/specs/device.yaml
include tinymovr/specs/dfu.yaml
Loading

0 comments on commit c746b82

Please sign in to comment.