Skip to content

Commit e2df8e9

Browse files
authored
Merge pull request #730 from odriverobotics/devel
Fw v0.5.6 Release Candidate
2 parents e89d71a + b968a67 commit e2df8e9

21 files changed

+1658
-407
lines changed

.gitignore

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -65,3 +65,4 @@ GUI/node_modules
6565
GUI/build
6666

6767
docs/reStructuredText/_build/
68+
tools/odrive-cansimple.ini

CHANGELOG.md

Lines changed: 38 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,42 @@
1-
# Unreleased Features
2-
Please add a note of your changes below this heading if you make a Pull Request.
31

4-
# Releases
2+
## [0.5.6] - Unreleased
3+
4+
### Fixed
5+
6+
* Fixed race condition in homing sequence that was causing strange behaviour. Fixes [#634](https://github.com/odriverobotics/ODrive/issues/634)]
7+
* When using a load encoder, CAN will report the correct position and velocity.
8+
* When using a load encoder, homing will reset the correct linear position. Fixes [#651](https://github.com/odriverobotics/ODrive/issues/651)
9+
* Implemented CAN controller error message, which was previously defined but not actually implemented.
10+
* Get Vbus Voltage message updated to match ODrive Pro's CANSimple implementation.
11+
* `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)
12+
13+
### Added
14+
15+
* 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)
16+
* 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)
17+
* Added CAN heartbeat message flags for motor, controller, and encoder error. If flag is true, fetch the corresponding error with the respective message.
18+
* Added scoped enums, e.g. `CONTROL_MODE_POSITION_CONTROL` can be used as `ControlMode.POSITION_CONTROL`
19+
* 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:
20+
21+
Command ID | Rate Variable | Message Name
22+
:-- | :-- | :--
23+
0x01 | `heartbeat_rate_ms` | Heartbeat
24+
0x09 | `encoder_rate_ms` | Get Encoder Estimates
25+
0x03 | `motor_error_rate_ms` | Get Motor Error
26+
0x04 | `encoder_error_rate_ms` | Get Encoder Error
27+
0x1D | `controller_error_rate_ms` | Get Controller Error
28+
0x05 | `sensorless_error_rate_ms` | Get Sensorless Error
29+
0x0A | `encoder_count_rate_ms` | Get Encoder Count
30+
0x14 | `iq_rate_ms` | Get Iq
31+
0x15 | `sensorless_rate_ms` | Get Sensorless Estimates
32+
0x17 | `bus_vi_rate_ms` | Get Bus Voltage Current
33+
34+
### Changed
35+
36+
* Improved can_generate_dbc.py file and resultant .dbc. Now supports 8 ODrive axes (0..7) natively
37+
* Add units and value tables to every signal in odrive-cansimple.dbc
38+
* Autogenerate odrive-cansimple.dbc on compile
39+
540
## [0.5.5] - 2022-08-11
641

742
* CANSimple messages which previously required the rtr bit to be set will now also respond if DLC = 0

Firmware/Makefile

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,7 @@ all:
3333
@tup --quiet -no-environ-check
3434
@$(PY_CMD) interface_generator_stub.py --definitions odrive-interface.yaml --template ../tools/enums_template.j2 --output ../tools/odrive/enums.py
3535
@$(PY_CMD) interface_generator_stub.py --definitions odrive-interface.yaml --template ../tools/arduino_enums_template.j2 --output ../Arduino/ODriveArduino/ODriveEnums.h
36+
@cd ../tools/ && $(PY_CMD) create_can_dbc.py
3637

3738
# Copy libfibre files to odrivetool if they were built
3839
@ ! test -f "fibre-cpp/build/libfibre-linux-amd64.so" || cp fibre-cpp/build/libfibre-linux-amd64.so ../tools/odrive/pyfibre/fibre/

Firmware/MotorControl/axis.cpp

Lines changed: 18 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -354,9 +354,6 @@ bool Axis::run_closed_loop_control_loop() {
354354
// Slowly drive in the negative direction at homing_speed until the min endstop is pressed
355355
// When pressed, set the linear count to the offset (default 0), and then go to position 0
356356
bool Axis::run_homing() {
357-
Controller::ControlMode stored_control_mode = controller_.config_.control_mode;
358-
Controller::InputMode stored_input_mode = controller_.config_.input_mode;
359-
360357
// TODO: theoretically this check should be inside the update loop,
361358
// otherwise someone could disable the endstop while homing is in progress.
362359
if (!min_endstop_.config_.enabled) {
@@ -424,13 +421,20 @@ bool Axis::run_homing() {
424421
return false;
425422
}
426423

427-
// Set the current position to 0.
428-
encoder_.set_linear_count(0);
429-
controller_.input_pos_ = 0;
424+
// Set the current position to 0, the target to zero, and make sure we're path planning from 0 to 0
425+
encoder_.set_linear_count(0);
426+
const auto load_encoder_axis = controller_.config_.load_encoder_axis;
427+
if(load_encoder_axis != axis_num_ && load_encoder_axis < AXIS_COUNT) {
428+
axes[load_encoder_axis].encoder_.set_linear_count(0);
429+
}
430+
controller_.input_pos_ = 0.0f;
431+
controller_.pos_setpoint_ = 0.0f;
432+
controller_.vel_setpoint_ = 0.0f;
430433
controller_.input_pos_updated();
431434

432-
controller_.config_.control_mode = stored_control_mode;
433-
controller_.config_.input_mode = stored_input_mode;
435+
// Force encoder estimate to update
436+
osDelay(1);
437+
434438
homing_.is_homed = true;
435439

436440
return check_for_errors();
@@ -540,9 +544,13 @@ void Axis::run_state_machine_loop() {
540544
} break;
541545

542546
case AXIS_STATE_HOMING: {
543-
//if (odrv.any_error())
544-
// goto invalid_state_label;
547+
Controller::ControlMode stored_control_mode = controller_.config_.control_mode;
548+
Controller::InputMode stored_input_mode = controller_.config_.input_mode;
549+
545550
status = run_homing();
551+
552+
controller_.config_.control_mode = stored_control_mode;
553+
controller_.config_.input_mode = stored_input_mode;
546554
} break;
547555

548556
case AXIS_STATE_ENCODER_OFFSET_CALIBRATION: {

Firmware/MotorControl/axis.hpp

Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -56,6 +56,14 @@ class Axis : public ODriveIntf::AxisIntf {
5656
bool is_extended = false;
5757
uint32_t heartbeat_rate_ms = 100;
5858
uint32_t encoder_rate_ms = 10;
59+
uint32_t motor_error_rate_ms = 0;
60+
uint32_t encoder_error_rate_ms = 0;
61+
uint32_t controller_error_rate_ms = 0;
62+
uint32_t sensorless_error_rate_ms = 0;
63+
uint32_t encoder_count_rate_ms = 0;
64+
uint32_t iq_rate_ms = 0;
65+
uint32_t sensorless_rate_ms = 0;
66+
uint32_t bus_vi_rate_ms = 0;
5967
};
6068

6169
struct Config_t {
@@ -101,6 +109,14 @@ class Axis : public ODriveIntf::AxisIntf {
101109
struct CAN_t {
102110
uint32_t last_heartbeat = 0;
103111
uint32_t last_encoder = 0;
112+
uint32_t last_motor_error = 0;
113+
uint32_t last_encoder_error = 0;
114+
uint32_t last_controller_error = 0;
115+
uint32_t last_sensorless_error = 0;
116+
uint32_t last_encoder_count = 0;
117+
uint32_t last_iq = 0;
118+
uint32_t last_sensorless = 0;
119+
uint32_t last_bus_vi = 0;
104120
};
105121

106122
Axis(int axis_num,

Firmware/MotorControl/controller.cpp

Lines changed: 22 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,7 @@
11

22
#include "odrive_main.h"
33
#include <algorithm>
4+
#include <numeric>
45

56
bool Controller::apply_config() {
67
config_.parent = this;
@@ -53,6 +54,20 @@ void Controller::start_anticogging_calibration() {
5354
}
5455
}
5556

57+
float Controller::remove_anticogging_bias()
58+
{
59+
auto& cogmap = config_.anticogging.cogging_map;
60+
61+
auto sum = std::accumulate(std::begin(cogmap), std::end(cogmap), 0.0f);
62+
auto average = sum / std::size(cogmap);
63+
64+
for(auto& val : cogmap) {
65+
val -= average;
66+
}
67+
68+
return average;
69+
}
70+
5671

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

268283
}
269284

285+
// Never command a setpoint beyond its limit
286+
if(config_.enable_vel_limit) {
287+
vel_setpoint_ = std::clamp(vel_setpoint_, -config_.vel_limit, config_.vel_limit);
288+
}
289+
const float Tlim = axis_->motor_.max_available_torque();
290+
torque_setpoint_ = std::clamp(torque_setpoint_, -Tlim, Tlim);
291+
270292
// Position control
271293
// TODO Decide if we want to use encoder or pll position here
272294
float gain_scheduling_multiplier = 1.0f;
@@ -373,7 +395,6 @@ bool Controller::update() {
373395

374396
// Torque limiting
375397
bool limited = false;
376-
float Tlim = axis_->motor_.max_available_torque();
377398
if (torque > Tlim) {
378399
limited = true;
379400
torque = Tlim;

Firmware/MotorControl/controller.hpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -81,7 +81,12 @@ class Controller : public ODriveIntf::ControllerIntf {
8181

8282
// TODO: make this more similar to other calibration loops
8383
void start_anticogging_calibration();
84+
float remove_anticogging_bias();
8485
bool anticogging_calibration(float pos_estimate, float vel_estimate);
86+
87+
float get_anticogging_value(uint32_t index) {
88+
return (index < 3600) ? config_.anticogging.cogging_map[index] : 0.0f;
89+
}
8590

8691
void update_filter_gains();
8792
bool update();

Firmware/MotorControl/endstop.hpp

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,6 @@ class Endstop {
1818
void set_debounce_ms(uint32_t value) { debounce_ms = value; parent->apply_config(); }
1919
};
2020

21-
Endstop() {}
2221

2322
Endstop::Config_t config_;
2423
Axis* axis_ = nullptr;

Firmware/Tupfile.lua

Lines changed: 14 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -328,9 +328,16 @@ boards = {
328328

329329
-- Toolchain setup -------------------------------------------------------------
330330

331-
CC='arm-none-eabi-gcc -std=c99'
332-
CXX='arm-none-eabi-g++ -std=c++17 -Wno-register'
333-
LINKER='arm-none-eabi-g++'
331+
CCPATH = tup.getconfig('ARM_COMPILER_PATH')
332+
if CCPATH == "" then
333+
CCPATH=''
334+
else
335+
CCPATH = CCPATH..'/'
336+
end
337+
338+
CC=CCPATH..'arm-none-eabi-gcc -std=c99'
339+
CXX=CCPATH..'arm-none-eabi-g++ -std=c++17 -Wno-register'
340+
LINKER=CCPATH..'arm-none-eabi-g++'
334341

335342
-- C-specific flags
336343
CFLAGS += '-D__weak="__attribute__((weak))"'
@@ -440,13 +447,13 @@ tup.frule{
440447
outputs={'build/ODriveFirmware.elf', extra_outputs={'build/ODriveFirmware.map'}}
441448
}
442449
-- display the size
443-
tup.frule{inputs={'build/ODriveFirmware.elf'}, command='arm-none-eabi-size %f'}
450+
tup.frule{inputs={'build/ODriveFirmware.elf'}, command=CCPATH..'arm-none-eabi-size %f'}
444451
-- create *.hex and *.bin output formats
445-
tup.frule{inputs={'build/ODriveFirmware.elf'}, command='arm-none-eabi-objcopy -O ihex %f %o', outputs={'build/ODriveFirmware.hex'}}
446-
tup.frule{inputs={'build/ODriveFirmware.elf'}, command='arm-none-eabi-objcopy -O binary -S %f %o', outputs={'build/ODriveFirmware.bin'}}
452+
tup.frule{inputs={'build/ODriveFirmware.elf'}, command=CCPATH..'arm-none-eabi-objcopy -O ihex %f %o', outputs={'build/ODriveFirmware.hex'}}
453+
tup.frule{inputs={'build/ODriveFirmware.elf'}, command=CCPATH..'arm-none-eabi-objcopy -O binary -S %f %o', outputs={'build/ODriveFirmware.bin'}}
447454

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

452459
if tup.getconfig('DOCTEST') == 'true' then

0 commit comments

Comments
 (0)