Skip to content

Commit

Permalink
Merge remote-tracking branch 'origin/devel' into control-loop-refactor
Browse files Browse the repository at this point in the history
  • Loading branch information
samuelsadok committed Sep 22, 2020
2 parents 89f0722 + b089573 commit 3addf6d
Show file tree
Hide file tree
Showing 19 changed files with 214 additions and 29 deletions.
5 changes: 5 additions & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
# Unreleased Features
Please add a note of your changes below this heading if you make a Pull Request.
### Added
* [Mechanical brake support](docs/mechanical-brakes.md)

### Changed

Expand Down Expand Up @@ -63,6 +65,9 @@ Please add a note of your changes below this heading if you make a Pull Request.
* `axis.motor.thermal_current_lim` has been removed. Instead a new property is available `axis.motor.effective_current_lim` which contains the effective current limit including any thermal limits.
* `axis.motor.get_inverter_temp()`, `axis.motor.inverter_temp_limit_lower` and `axis.motor.inverter_temp_limit_upper` have been moved to seperate fet thermistor object under `axis.fet_thermistor`. `get_inverter_temp()` function has been renamed to `temp` and is now a read-only property.
* `axis.config.counts_per_step` is now `axis.config.turns_per_step`
* Outputs of `axis.sensorless_estimator` are now in turns/s instead of electrical rad/s
* Fixed bug of high current during lockin-ramp caused by `motor::update()` expecting a torque command instead of current
* Fixed bug where commanded velocity was extremely high just after sensorless ramp when using `input_mode` INPUT_MODE_VEL_RAMP caused by `vel_setpoint` and `axis.config.sensorless_ramp.vel` being in different units


# Releases
Expand Down
3 changes: 3 additions & 0 deletions Firmware/Board/v3/board.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,6 +102,7 @@ Encoder encoders[AXIS_COUNT] = {

// TODO: this has no hardware dependency and should be allocated depending on config
Endstop endstops[2 * AXIS_COUNT];
MechanicalBrake mechanical_brakes[AXIS_COUNT];

SensorlessEstimator sensorless_estimators[AXIS_COUNT];
Controller controllers[AXIS_COUNT];
Expand All @@ -122,6 +123,7 @@ std::array<Axis, AXIS_COUNT> axes{{
motors[0], // motor
trap[0], // trap
endstops[0], endstops[1], // min_endstop, max_endstop
mechanical_brakes[0], // mechanical brake
},
{
1, // axis_num
Expand All @@ -141,6 +143,7 @@ std::array<Axis, AXIS_COUNT> axes{{
motors[1], // motor
trap[1], // trap
endstops[2], endstops[3], // min_endstop, max_endstop
mechanical_brakes[1], // mechanical brake
},
}};

Expand Down
6 changes: 5 additions & 1 deletion Firmware/MotorControl/axis.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,8 @@ Axis::Axis(int axis_num,
Motor& motor,
TrapezoidalTrajectory& trap,
Endstop& min_endstop,
Endstop& max_endstop)
Endstop& max_endstop,
MechanicalBrake& mechanical_brake)
: axis_num_(axis_num),
default_step_gpio_pin_(default_step_gpio_pin),
default_dir_gpio_pin_(default_dir_gpio_pin),
Expand All @@ -33,6 +34,7 @@ Axis::Axis(int axis_num,
trap_traj_(trap),
min_endstop_(min_endstop),
max_endstop_(max_endstop),
mechanical_brake_(mechanical_brake),
current_limiters_(make_array(
static_cast<CurrentLimiter*>(&fet_thermistor),
static_cast<CurrentLimiter*>(&motor_thermistor))),
Expand All @@ -49,6 +51,7 @@ Axis::Axis(int axis_num,
trap_traj_.axis_ = this;
min_endstop_.axis_ = this;
max_endstop_.axis_ = this;
mechanical_brake_.axis_ = this;
}

Axis::LockinConfig_t Axis::default_calibration() {
Expand Down Expand Up @@ -432,6 +435,7 @@ bool Axis::run_homing() {
}

bool Axis::run_idle_loop() {
mechanical_brake_.engage();
set_step_dir_active(config_.enable_step_dir && config_.step_dir_always_on);
while (requested_state_ == AXIS_STATE_UNDEFINED) {
motor_.setup();
Expand Down
5 changes: 4 additions & 1 deletion Firmware/MotorControl/axis.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@ class Axis;
#include "open_loop_controller.hpp"
#include "trapTraj.hpp"
#include "endstop.hpp"
#include "mechanical_brake.hpp"
#include "low_level.h"
#include "utils.hpp"
#include "task_timer.hpp"
Expand Down Expand Up @@ -105,7 +106,8 @@ class Axis : public ODriveIntf::AxisIntf {
Motor& motor,
TrapezoidalTrajectory& trap,
Endstop& min_endstop,
Endstop& max_endstop);
Endstop& max_endstop,
MechanicalBrake& mechanical_brake);

bool apply_config();
void clear_config();
Expand Down Expand Up @@ -160,6 +162,7 @@ class Axis : public ODriveIntf::AxisIntf {
TrapezoidalTrajectory& trap_traj_;
Endstop& min_endstop_;
Endstop& max_endstop_;
MechanicalBrake& mechanical_brake_;
TaskTimes task_times_;

// List of current_limiters and thermistors to
Expand Down
3 changes: 2 additions & 1 deletion Firmware/MotorControl/encoder.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,10 @@
#include "utils.hpp"
#include <autogen/interfaces.hpp>


class Encoder : public ODriveIntf::EncoderIntf {
public:
const uint32_t MODE_FLAG_ABS = 0x100;
static constexpr uint32_t MODE_FLAG_ABS = 0x100;

struct Config_t {
Mode mode = MODE_INCREMENTAL;
Expand Down
16 changes: 16 additions & 0 deletions Firmware/MotorControl/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@ static bool config_read_all() {
config_manager.read(&axes[i].trap_traj_.config_) &&
config_manager.read(&axes[i].min_endstop_.config_) &&
config_manager.read(&axes[i].max_endstop_.config_) &&
config_manager.read(&axes[i].mechanical_brake_.config_) &&
config_manager.read(&motors[i].config_) &&
config_manager.read(&fet_thermistors[i].config_) &&
config_manager.read(&axes[i].motor_thermistor_.config_) &&
Expand All @@ -64,6 +65,7 @@ static bool config_write_all() {
config_manager.write(&axes[i].trap_traj_.config_) &&
config_manager.write(&axes[i].min_endstop_.config_) &&
config_manager.write(&axes[i].max_endstop_.config_) &&
config_manager.write(&axes[i].mechanical_brake_.config_) &&
config_manager.write(&motors[i].config_) &&
config_manager.write(&fet_thermistors[i].config_) &&
config_manager.write(&axes[i].motor_thermistor_.config_) &&
Expand All @@ -83,6 +85,7 @@ static void config_clear_all() {
axes[i].trap_traj_.config_ = {};
axes[i].min_endstop_.config_ = {};
axes[i].max_endstop_.config_ = {};
axes[i].mechanical_brake_.config_ = {};
motors[i].config_ = {};
fet_thermistors[i].config_ = {};
axes[i].motor_thermistor_.config_ = {};
Expand Down Expand Up @@ -385,6 +388,13 @@ static void rtos_main(void*) {
// must happen after communication is initialized
pwm0_input.init();

// Set up the CS pins for absolute encoders (TODO: move to GPIO init switch statement)
for(auto& axis : axes){
if(axis.encoder_.config_.mode & Encoder::MODE_FLAG_ABS){
axis.encoder_.abs_spi_cs_pin_init();
}
}

// Try to initialized gate drivers for fault-free startup.
// If this does not succeed, a fault will be raised and the idle loop will
// periodically attempt to reinit the gate driver.
Expand Down Expand Up @@ -526,6 +536,7 @@ extern "C" int main(void) {
if (mode == ODriveIntf::GPIO_MODE_DIGITAL ||
mode == ODriveIntf::GPIO_MODE_DIGITAL_PULL_UP ||
mode == ODriveIntf::GPIO_MODE_DIGITAL_PULL_DOWN ||
mode == ODriveIntf::GPIO_MODE_MECH_BRAKE ||
mode == ODriveIntf::GPIO_MODE_ANALOG_IN) {
GPIO_InitStruct.Alternate = 0;
} else {
Expand Down Expand Up @@ -622,6 +633,11 @@ extern "C" int main(void) {
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
} break;
case ODriveIntf::GPIO_MODE_MECH_BRAKE: {
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
} break;
default: {
odrv.misconfigured_ = true;
continue;
Expand Down
13 changes: 13 additions & 0 deletions Firmware/MotorControl/mechanical_brake.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
#include <odrive_main.h>

void MechanicalBrake::engage() {
if (odrv.config_.gpio_modes[config_.gpio_num] == ODriveIntf::GPIO_MODE_MECH_BRAKE){
get_gpio(config_.gpio_num).write(config_.is_active_low ? 0 : 1);
}
}

void MechanicalBrake::release() {
if (odrv.config_.gpio_modes[config_.gpio_num] == ODriveIntf::GPIO_MODE_MECH_BRAKE){
get_gpio(config_.gpio_num).write(config_.is_active_low ? 1 : 0);
}
}
25 changes: 25 additions & 0 deletions Firmware/MotorControl/mechanical_brake.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
#ifndef __MECHANICAL_BRAKE_HPP
#define __MECHANICAL_BRAKE_HPP

#include <autogen/interfaces.hpp>

class MechanicalBrake : public ODriveIntf::MechanicalBrakeIntf {
public:
struct Config_t {
uint16_t gpio_num = 0;
bool is_active_low = true;

// custom setters
MechanicalBrake* parent = nullptr;
void set_gpio_num(uint16_t value) { gpio_num = value; }
};

MechanicalBrake() {}

MechanicalBrake::Config_t config_;
Axis* axis_ = nullptr;

void release();
void engage();
};
#endif // __MECHANICAL_BRAKE_HPP
2 changes: 2 additions & 0 deletions Firmware/MotorControl/motor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -168,6 +168,8 @@ Motor::Motor(TIM_HandleTypeDef* timer,
* @returns: True on success, false otherwise
*/
bool Motor::arm(PhaseControlLaw<3>* control_law) {
axis_->mechanical_brake_.release();

CRITICAL_SECTION() {
control_law_ = control_law;

Expand Down
1 change: 1 addition & 0 deletions Firmware/MotorControl/odrive_main.h
Original file line number Diff line number Diff line change
Expand Up @@ -140,6 +140,7 @@ inline ENUMTYPE operator ~ (ENUMTYPE a) { return static_cast<ENUMTYPE>(~static_c
#include <thermistor.hpp>
#include <trapTraj.hpp>
#include <endstop.hpp>
#include <mechanical_brake.hpp>
#include <axis.hpp>
#include <oscilloscope.hpp>
#include <communication/communication.h>
Expand Down
4 changes: 2 additions & 2 deletions Firmware/MotorControl/sensorless_estimator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -82,8 +82,8 @@ bool SensorlessEstimator::update() {
pll_pos_ = wrap_pm_pi(pll_pos_ + current_meas_period * pll_kp * delta_phase);
// update PLL velocity
phase_vel_ += current_meas_period * pll_ki * delta_phase;

vel_estimate_ = phase_vel_ / (2 * M_PI);
// convert to mechanical turns/s for controller usage.
vel_estimate_ = phase_vel_ / (std::max((float)axis_->motor_.config_.pole_pairs, 1.0f) * 2.0f * M_PI);

return true;
};
1 change: 1 addition & 0 deletions Firmware/Tupfile.lua
Original file line number Diff line number Diff line change
Expand Up @@ -190,6 +190,7 @@ sources = {
'MotorControl/encoder.cpp',
'MotorControl/endstop.cpp',
'MotorControl/async_estimator.cpp',
'MotorControl/mechanical_brake.cpp',
'MotorControl/controller.cpp',
'MotorControl/foc.cpp',
'MotorControl/open_loop_controller.cpp',
Expand Down
19 changes: 18 additions & 1 deletion Firmware/odrive-interface.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -468,6 +468,7 @@ interfaces:
trap_traj: TrapezoidalTrajectory
min_endstop: Endstop
max_endstop: Endstop
mechanical_brake: MechanicalBrake
task_times:
c_is_class: False
attributes:
Expand Down Expand Up @@ -990,7 +991,6 @@ interfaces:
accel_limit: float32
decel_limit: float32


ODrive.Endstop:
c_is_class: True
attributes:
Expand All @@ -1004,6 +1004,22 @@ interfaces:
is_active_high: bool
debounce_ms: {type: uint32, c_setter: set_debounce_ms}

ODrive.MechanicalBrake:
c_is_class: True
attributes:
config:
c_is_class: False
attributes:
gpio_num: {type: uint16, c_setter: set_gpio_num}
is_active_low: bool
functions:
engage:
doc: |
This function engages the mechanical brake if one is present and enabled.
release:
doc: |
This function releases the mecahncal brake if one is present and enabled.
ODrive.TaskTimer:
c_is_class: True
attributes:
Expand Down Expand Up @@ -1039,6 +1055,7 @@ valuetypes:
Enc0: {doc: The pin is used by quadrature encoder 0.}
Enc1: {doc: The pin is used by quadrature encoder 1.}
Enc2: {doc: This mode is not supported on ODrive v3.x.}
MechBrake: {doc: This is to support external mechanical brakes.}

ODrive.Can.Protocol:
values: {Simple: }
Expand Down
2 changes: 2 additions & 0 deletions docs/_data/index.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@ sections:
url: /encoders
- title: Homing & Endstops
url: /endstops
- title: Mechanical Brakes
url: /mechanical-brakes
- title: Thermistors
url: /thermistors
- title: Control & Tuning
Expand Down
8 changes: 4 additions & 4 deletions docs/commands.md
Original file line number Diff line number Diff line change
Expand Up @@ -81,15 +81,15 @@ All variables that are part of a `[...].config` object can be saved to non-volat
## Setting up sensorless
The ODrive can run without encoder/hall feedback, but there is a minimum speed, usually around a few hunderd RPM.

To give an example, suppose you have a motor with 7 pole pairs, and you want to spin it at 3000 RPM. Then you would set the `input_vel` to `3000 * 2*pi/60 * 7 = 2199 rad/s electrical`.

Below are some suggested starting parameters that you can use. Note that you _must_ set the `pm_flux_linkage` correctly for sensorless mode to work.
Below are some suggested starting parameters that you can use. Note that you _must_ set the `pm_flux_linkage` correctly for sensorless mode to work. Motor calibration and setup must also be completed before sensorless mode will work.

```
odrv0.axis0.controller.config.vel_gain = 0.01
odrv0.axis0.controller.config.vel_integrator_gain = 0.05
odrv0.axis0.controller.config.control_mode = 2
odrv0.axis0.controller.input_vel = 400
odrv0.axis0.controller.input_vel = 10
odrv0.axis0.controller.config.vel_limit = <a value greater than input_vel>
odrv0.axis0.motor.config.current_lim = 2 * odrv0.axis0.config.sensorless_ramp.current
odrv0.axis0.sensorless_estimator.config.pm_flux_linkage = 5.51328895422 / (<pole pairs> * <motor kv>)
odrv0.axis0.config.enable_sensorless_mode = True
```
Expand Down
Loading

0 comments on commit 3addf6d

Please sign in to comment.