Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fw v0.5.6 Release Candidate #730

Merged
merged 32 commits into from
Apr 29, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
32 commits
Select commit Hold shift + click to select a range
73b15f2
Add get_adc_voltage()
Malaphor Aug 19, 2022
398ee3d
Added docs info
Malaphor Aug 31, 2022
3985bb7
Merge pull request #707 from Malaphor/devel2-electric_boogaloo
Wetmelon Sep 6, 2022
45fee3a
Add controller error message
Wetmelon Sep 6, 2022
49080cb
Add to docs table
Wetmelon Sep 6, 2022
317d09a
Update .dbc
Wetmelon Sep 6, 2022
08d5a20
Fix homing running off when it's done
Wetmelon Sep 6, 2022
64bbfea
Ensure pos_estimate is updated at least once after homing
Wetmelon Sep 6, 2022
b17a4a6
Always restore control and input mode after leaving homing
Wetmelon Sep 6, 2022
6131bc0
Merge pull request #709 from odriverobotics/can_controller_error
Wetmelon Sep 6, 2022
52384ff
Merge branch 'devel' into hotfix/homing_fix
Wetmelon Sep 6, 2022
fba8106
Update vbus_voltage message to match Pro
Wetmelon Sep 6, 2022
54a1659
Merge pull request #712 from odriverobotics/can_sync
Wetmelon Sep 7, 2022
e64e9a5
Add to changelog
Wetmelon Sep 7, 2022
fb70a83
Merge pull request #710 from odriverobotics/hotfix/homing_fix
Wetmelon Sep 7, 2022
315845c
Bump jszip from 3.5.0 to 3.10.1 in /GUI
dependabot[bot] Sep 8, 2022
e85b29a
Update CAN dbc
Wetmelon Sep 10, 2022
653bd27
Merge pull request #714 from odriverobotics/can_dbc
Wetmelon Sep 14, 2022
989307b
Merge pull request #713 from odriverobotics/dependabot/npm_and_yarn/G…
Wetmelon Sep 21, 2022
e9d1b33
Can heartbeat flags (#711)
Malaphor Sep 22, 2022
5f9b45e
Add heartbeat flags to .dbc
Wetmelon Sep 22, 2022
073da34
Fix load encoder issues
Wetmelon Sep 21, 2022
3056a4c
Add function to index into cogmap (#716)
Wetmelon Sep 22, 2022
f64c075
Update changelog
Wetmelon Sep 22, 2022
e88fa10
Make vel_ramp safer by limiting the vel_setpoint to vel_limit
Wetmelon Sep 22, 2022
8a517f8
Update changelog
Wetmelon Sep 22, 2022
9a75403
Add value tables and units to every signal in .dbc
Wetmelon Sep 26, 2022
5c039a9
Add CONFIG_ARM_COMPILER_PATH
Wetmelon Sep 23, 2021
39d66b0
Add more cyclic messages
Wetmelon Oct 11, 2022
f14caad
Merge branch 'more_cyclics' into devel
Wetmelon Oct 24, 2022
50f2692
Update docs and changelog
Wetmelon Oct 24, 2022
b968a67
Add function to remove anticogging bias
Wetmelon Mar 8, 2023
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -65,3 +65,4 @@ GUI/node_modules
GUI/build

docs/reStructuredText/_build/
tools/odrive-cansimple.ini
41 changes: 38 additions & 3 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
@@ -1,7 +1,42 @@
# Unreleased Features
Please add a note of your changes below this heading if you make a Pull Request.

# Releases
## [0.5.6] - Unreleased

### Fixed

* Fixed race condition in homing sequence that was causing strange behaviour. Fixes [#634](https://github.com/odriverobotics/ODrive/issues/634)]
* When using a load encoder, CAN will report the correct position and velocity.
* When using a load encoder, homing will reset the correct linear position. Fixes [#651](https://github.com/odriverobotics/ODrive/issues/651)
* Implemented CAN controller error message, which was previously defined but not actually implemented.
* Get Vbus Voltage message updated to match ODrive Pro's CANSimple implementation.
* `vel_setpoint` and `torque_setpoint` will be clamped to `vel_limit` and the active torque limit. Fixes [#647](https://github.com/odriverobotics/ODrive/issues/647)

### Added

* Added public `controller.get_anticogging_value(uint32)` fibre function to index into the the cogging map. Fixes [#690](https://github.com/odriverobotics/ODrive/issues/690)
* Added Get ADC Voltage message to CAN (0x1C). Send the desired GPIO number in byte 1, and the ODrive will respond with the ADC voltage from that pin (if previously configured for analog)
* Added CAN heartbeat message flags for motor, controller, and encoder error. If flag is true, fetch the corresponding error with the respective message.
* Added scoped enums, e.g. `CONTROL_MODE_POSITION_CONTROL` can be used as `ControlMode.POSITION_CONTROL`
* Added more cyclic messages to can. Use the `rate_ms` values in `<odrv>.<axis>.config.can` to set the cycle rate of the message in milliseconds. Set a rate to 0 to disable sending. The following variables are avaialble:

Command ID | Rate Variable | Message Name
:-- | :-- | :--
0x01 | `heartbeat_rate_ms` | Heartbeat
0x09 | `encoder_rate_ms` | Get Encoder Estimates
0x03 | `motor_error_rate_ms` | Get Motor Error
0x04 | `encoder_error_rate_ms` | Get Encoder Error
0x1D | `controller_error_rate_ms` | Get Controller Error
0x05 | `sensorless_error_rate_ms` | Get Sensorless Error
0x0A | `encoder_count_rate_ms` | Get Encoder Count
0x14 | `iq_rate_ms` | Get Iq
0x15 | `sensorless_rate_ms` | Get Sensorless Estimates
0x17 | `bus_vi_rate_ms` | Get Bus Voltage Current

### Changed

* Improved can_generate_dbc.py file and resultant .dbc. Now supports 8 ODrive axes (0..7) natively
* Add units and value tables to every signal in odrive-cansimple.dbc
* Autogenerate odrive-cansimple.dbc on compile

## [0.5.5] - 2022-08-11

* CANSimple messages which previously required the rtr bit to be set will now also respond if DLC = 0
Expand Down
1 change: 1 addition & 0 deletions Firmware/Makefile
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@ all:
@tup --quiet -no-environ-check
@$(PY_CMD) 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/arduino_enums_template.j2 --output ../Arduino/ODriveArduino/ODriveEnums.h
@cd ../tools/ && $(PY_CMD) create_can_dbc.py

# Copy libfibre files to odrivetool if they were built
@ ! test -f "fibre-cpp/build/libfibre-linux-amd64.so" || cp fibre-cpp/build/libfibre-linux-amd64.so ../tools/odrive/pyfibre/fibre/
Expand Down
28 changes: 18 additions & 10 deletions Firmware/MotorControl/axis.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -354,9 +354,6 @@ bool Axis::run_closed_loop_control_loop() {
// Slowly drive in the negative direction at homing_speed until the min endstop is pressed
// When pressed, set the linear count to the offset (default 0), and then go to position 0
bool Axis::run_homing() {
Controller::ControlMode stored_control_mode = controller_.config_.control_mode;
Controller::InputMode stored_input_mode = controller_.config_.input_mode;

// TODO: theoretically this check should be inside the update loop,
// otherwise someone could disable the endstop while homing is in progress.
if (!min_endstop_.config_.enabled) {
Expand Down Expand Up @@ -424,13 +421,20 @@ bool Axis::run_homing() {
return false;
}

// Set the current position to 0.
encoder_.set_linear_count(0);
controller_.input_pos_ = 0;
// Set the current position to 0, the target to zero, and make sure we're path planning from 0 to 0
encoder_.set_linear_count(0);
const auto load_encoder_axis = controller_.config_.load_encoder_axis;
if(load_encoder_axis != axis_num_ && load_encoder_axis < AXIS_COUNT) {
axes[load_encoder_axis].encoder_.set_linear_count(0);
}
controller_.input_pos_ = 0.0f;
controller_.pos_setpoint_ = 0.0f;
controller_.vel_setpoint_ = 0.0f;
controller_.input_pos_updated();

controller_.config_.control_mode = stored_control_mode;
controller_.config_.input_mode = stored_input_mode;
// Force encoder estimate to update
osDelay(1);

homing_.is_homed = true;

return check_for_errors();
Expand Down Expand Up @@ -540,9 +544,13 @@ void Axis::run_state_machine_loop() {
} break;

case AXIS_STATE_HOMING: {
//if (odrv.any_error())
// goto invalid_state_label;
Controller::ControlMode stored_control_mode = controller_.config_.control_mode;
Controller::InputMode stored_input_mode = controller_.config_.input_mode;

status = run_homing();

controller_.config_.control_mode = stored_control_mode;
controller_.config_.input_mode = stored_input_mode;
} break;

case AXIS_STATE_ENCODER_OFFSET_CALIBRATION: {
Expand Down
16 changes: 16 additions & 0 deletions Firmware/MotorControl/axis.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,6 +56,14 @@ class Axis : public ODriveIntf::AxisIntf {
bool is_extended = false;
uint32_t heartbeat_rate_ms = 100;
uint32_t encoder_rate_ms = 10;
uint32_t motor_error_rate_ms = 0;
uint32_t encoder_error_rate_ms = 0;
uint32_t controller_error_rate_ms = 0;
uint32_t sensorless_error_rate_ms = 0;
uint32_t encoder_count_rate_ms = 0;
uint32_t iq_rate_ms = 0;
uint32_t sensorless_rate_ms = 0;
uint32_t bus_vi_rate_ms = 0;
};

struct Config_t {
Expand Down Expand Up @@ -101,6 +109,14 @@ class Axis : public ODriveIntf::AxisIntf {
struct CAN_t {
uint32_t last_heartbeat = 0;
uint32_t last_encoder = 0;
uint32_t last_motor_error = 0;
uint32_t last_encoder_error = 0;
uint32_t last_controller_error = 0;
uint32_t last_sensorless_error = 0;
uint32_t last_encoder_count = 0;
uint32_t last_iq = 0;
uint32_t last_sensorless = 0;
uint32_t last_bus_vi = 0;
};

Axis(int axis_num,
Expand Down
23 changes: 22 additions & 1 deletion Firmware/MotorControl/controller.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@

#include "odrive_main.h"
#include <algorithm>
#include <numeric>

bool Controller::apply_config() {
config_.parent = this;
Expand Down Expand Up @@ -53,6 +54,20 @@ void Controller::start_anticogging_calibration() {
}
}

float Controller::remove_anticogging_bias()
{
auto& cogmap = config_.anticogging.cogging_map;

auto sum = std::accumulate(std::begin(cogmap), std::end(cogmap), 0.0f);
auto average = sum / std::size(cogmap);

for(auto& val : cogmap) {
val -= average;
}

return average;
}


/*
* This anti-cogging implementation iterates through each encoder position,
Expand Down Expand Up @@ -267,6 +282,13 @@ bool Controller::update() {

}

// Never command a setpoint beyond its limit
if(config_.enable_vel_limit) {
vel_setpoint_ = std::clamp(vel_setpoint_, -config_.vel_limit, config_.vel_limit);
}
const float Tlim = axis_->motor_.max_available_torque();
torque_setpoint_ = std::clamp(torque_setpoint_, -Tlim, Tlim);

// Position control
// TODO Decide if we want to use encoder or pll position here
float gain_scheduling_multiplier = 1.0f;
Expand Down Expand Up @@ -373,7 +395,6 @@ bool Controller::update() {

// Torque limiting
bool limited = false;
float Tlim = axis_->motor_.max_available_torque();
if (torque > Tlim) {
limited = true;
torque = Tlim;
Expand Down
5 changes: 5 additions & 0 deletions Firmware/MotorControl/controller.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,12 @@ class Controller : public ODriveIntf::ControllerIntf {

// TODO: make this more similar to other calibration loops
void start_anticogging_calibration();
float remove_anticogging_bias();
bool anticogging_calibration(float pos_estimate, float vel_estimate);

float get_anticogging_value(uint32_t index) {
return (index < 3600) ? config_.anticogging.cogging_map[index] : 0.0f;
}

void update_filter_gains();
bool update();
Expand Down
1 change: 0 additions & 1 deletion Firmware/MotorControl/endstop.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@ class Endstop {
void set_debounce_ms(uint32_t value) { debounce_ms = value; parent->apply_config(); }
};

Endstop() {}

Endstop::Config_t config_;
Axis* axis_ = nullptr;
Expand Down
21 changes: 14 additions & 7 deletions Firmware/Tupfile.lua
Original file line number Diff line number Diff line change
Expand Up @@ -328,9 +328,16 @@ boards = {

-- Toolchain setup -------------------------------------------------------------

CC='arm-none-eabi-gcc -std=c99'
CXX='arm-none-eabi-g++ -std=c++17 -Wno-register'
LINKER='arm-none-eabi-g++'
CCPATH = tup.getconfig('ARM_COMPILER_PATH')
if CCPATH == "" then
CCPATH=''
else
CCPATH = CCPATH..'/'
end

CC=CCPATH..'arm-none-eabi-gcc -std=c99'
CXX=CCPATH..'arm-none-eabi-g++ -std=c++17 -Wno-register'
LINKER=CCPATH..'arm-none-eabi-g++'

-- C-specific flags
CFLAGS += '-D__weak="__attribute__((weak))"'
Expand Down Expand Up @@ -440,13 +447,13 @@ tup.frule{
outputs={'build/ODriveFirmware.elf', extra_outputs={'build/ODriveFirmware.map'}}
}
-- display the size
tup.frule{inputs={'build/ODriveFirmware.elf'}, command='arm-none-eabi-size %f'}
tup.frule{inputs={'build/ODriveFirmware.elf'}, command=CCPATH..'arm-none-eabi-size %f'}
-- create *.hex and *.bin output formats
tup.frule{inputs={'build/ODriveFirmware.elf'}, command='arm-none-eabi-objcopy -O ihex %f %o', outputs={'build/ODriveFirmware.hex'}}
tup.frule{inputs={'build/ODriveFirmware.elf'}, command='arm-none-eabi-objcopy -O binary -S %f %o', outputs={'build/ODriveFirmware.bin'}}
tup.frule{inputs={'build/ODriveFirmware.elf'}, command=CCPATH..'arm-none-eabi-objcopy -O ihex %f %o', outputs={'build/ODriveFirmware.hex'}}
tup.frule{inputs={'build/ODriveFirmware.elf'}, command=CCPATH..'arm-none-eabi-objcopy -O binary -S %f %o', outputs={'build/ODriveFirmware.bin'}}

if tup.getconfig('ENABLE_DISASM') == 'true' then
tup.frule{inputs={'build/ODriveFirmware.elf'}, command='arm-none-eabi-objdump %f -dSC > %o', outputs={'build/ODriveFirmware.asm'}}
tup.frule{inputs={'build/ODriveFirmware.elf'}, command=CCPATH..'arm-none-eabi-objdump %f -dSC > %o', outputs={'build/ODriveFirmware.asm'}}
end

if tup.getconfig('DOCTEST') == 'true' then
Expand Down