Skip to content

Commit

Permalink
Merge branch 'devel' into uart1
Browse files Browse the repository at this point in the history
  • Loading branch information
samuelsadok committed Oct 16, 2020
2 parents e15ab60 + cc3b3c2 commit d6debf8
Show file tree
Hide file tree
Showing 112 changed files with 23,456 additions and 270 deletions.
15 changes: 11 additions & 4 deletions .github/workflows/documentation.yml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ name: Build and publish HTML documentation website

on:
push:
branches: [ feature/doc_autogen ]
branches: [ master ]

jobs:
jekyll:
Expand Down Expand Up @@ -52,15 +52,22 @@ jobs:
cd /srv/jekyll/docs && \
bundle config path vendor/bundle && \
bundle install && \
JEKYLL_ENV=production bundle exec jekyll build
bundle exec jekyll build --baseurl \"\"
cd ..
mv docs/_site _site
rm -rdf docs
mv _site docs
touch docs/.nojekyll
"
touch .nojekyll
# Extra checks to reduce likelihood of defect build
test -f docs/CNAME
test -f docs/index.html
- name: Push to documentation branch
run: |
git config user.name "${GITHUB_ACTOR}"
git config user.email "${GITHUB_ACTOR}@users.noreply.github.com"
git add -f docs/_site
git add -f docs
git commit -m "jekyll build from Action ${GITHUB_SHA}"
git push --force origin HEAD:${REMOTE_BRANCH}
env:
Expand Down
5 changes: 5 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -61,3 +61,8 @@ ODrive\.files
ODrive\.includes

Firmware/Tests/bin/

# GUI
GUI/dist_electron
GUI/node_modules
GUI/build
8 changes: 4 additions & 4 deletions Arduino/ODriveArduino/ODriveArduino.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,14 +59,14 @@ int32_t ODriveArduino::readInt() {
return readString().toInt();
}

bool ODriveArduino::run_state(int axis, int requested_state, bool wait) {
int timeout_ctr = 100;
bool ODriveArduino::run_state(int axis, int requested_state, bool wait_for_idle, float timeout) {
int timeout_ctr = (int)(timeout * 10.0f);
serial_ << "w axis" << axis << ".requested_state " << requested_state << '\n';
if (wait) {
if (wait_for_idle) {
do {
delay(100);
serial_ << "r axis" << axis << ".current_state\n";
} while (readInt() != requested_state && --timeout_ctr > 0);
} while (readInt() != AXIS_STATE_IDLE && --timeout_ctr > 0);
}

return timeout_ctr > 0;
Expand Down
2 changes: 1 addition & 1 deletion Arduino/ODriveArduino/ODriveArduino.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ class ODriveArduino {
int32_t readInt();

// State helper
bool run_state(int axis, int requested_state, bool wait);
bool run_state(int axis, int requested_state, bool wait_for_idle, float timeout = 10.0f);
private:
String readString();

Expand Down
Original file line number Diff line number Diff line change
@@ -1,14 +1,39 @@

// includes
#include <HardwareSerial.h>
#include <SoftwareSerial.h>
#include <ODriveArduino.h>

// Printing with stream operator
// Printing with stream operator helper functions
template<class T> inline Print& operator <<(Print &obj, T arg) { obj.print(arg); return obj; }
template<> inline Print& operator <<(Print &obj, float arg) { obj.print(arg, 4); return obj; }

// Serial to the ODrive
SoftwareSerial odrive_serial(8, 9); //RX (ODrive TX), TX (ODrive RX)
// Note: you must also connect GND on ODrive to GND on Arduino!

////////////////////////////////
// Set up serial pins to the ODrive
////////////////////////////////

// Below are some sample configurations.
// You can comment out the default Teensy one and uncomment the one you wish to use.
// You can of course use something different if you like
// Don't forget to also connect ODrive GND to Arduino GND.

// Teensy 3 and 4 (all versions) - Serial1
// pin 0: RX - connect to ODrive TX
// pin 1: TX - connect to ODrive RX
// See https://www.pjrc.com/teensy/td_uart.html for other options on Teensy
HardwareSerial& odrive_serial = Serial1;

// Arduino Mega or Due - Serial1
// pin 19: RX - connect to ODrive TX
// pin 18: TX - connect to ODrive RX
// See https://www.arduino.cc/reference/en/language/functions/communication/serial/ for other options
// HardwareSerial& odrive_serial = Serial1;

// Arduino without spare serial ports (such as Arduino UNO) have to use software serial.
// Note that this is implemented poorly and can lead to wrong data sent or read.
// pin 8: RX - connect to ODrive TX
// pin 9: TX - connect to ODrive RX
// SoftwareSerial odrive_serial(8, 9);


// ODrive object
ODriveArduino odrive(odrive_serial);
Expand All @@ -28,7 +53,7 @@ void setup() {
// You can of course set them different if you want.
// See the documentation or play around in odrivetool to see the available parameters
for (int axis = 0; axis < 2; ++axis) {
odrive_serial << "w axis" << axis << ".controller.config.vel_limit " << 22000.0f << '\n';
odrive_serial << "w axis" << axis << ".controller.config.vel_limit " << 10.0f << '\n';
odrive_serial << "w axis" << axis << ".motor.config.current_lim " << 11.0f << '\n';
// This ends up writing something like "w axis0.motor.config.current_lim 10.0\n"
}
Expand All @@ -52,23 +77,23 @@ void loop() {

requested_state = ODriveArduino::AXIS_STATE_MOTOR_CALIBRATION;
Serial << "Axis" << c << ": Requesting state " << requested_state << '\n';
odrive.run_state(motornum, requested_state, true);
if(!odrive.run_state(motornum, requested_state, true)) return;

requested_state = ODriveArduino::AXIS_STATE_ENCODER_OFFSET_CALIBRATION;
Serial << "Axis" << c << ": Requesting state " << requested_state << '\n';
odrive.run_state(motornum, requested_state, true);
if(!odrive.run_state(motornum, requested_state, true, 25.0f)) return;

requested_state = ODriveArduino::AXIS_STATE_CLOSED_LOOP_CONTROL;
Serial << "Axis" << c << ": Requesting state " << requested_state << '\n';
odrive.run_state(motornum, requested_state, false); // don't wait
if(!odrive.run_state(motornum, requested_state, false /*don't wait*/)) return;
}

// Sinusoidal test move
if (c == 's') {
Serial.println("Executing test move");
for (float ph = 0.0f; ph < 6.28318530718f; ph += 0.01f) {
float pos_m0 = 20000.0f * cos(ph);
float pos_m1 = 20000.0f * sin(ph);
float pos_m0 = 2.0f * cos(ph);
float pos_m1 = 2.0f * sin(ph);
odrive.SetPosition(0, pos_m0);
odrive.SetPosition(1, pos_m1);
delay(5);
Expand Down
10 changes: 7 additions & 3 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -18,26 +18,30 @@ Please add a note of your changes below this heading if you make a Pull Request.
* `<axis>.motor.gate_driver` was moved to `<axis>.gate_driver`.
* `<axis>.min_endstop.pullup` and `<axis>.max_endstop.pullup` were removed. Use `<odrv>.config.gpioX_mode = GPIO_MODE_DIGITAL / GPIO_MODE_DIGITAL_PULL_UP / GPIO_MODE_DIGITAL_PULL_DOWN` instead.

# Release Candidate
## [0.5.1] - Date TBD
# Releases
## [0.5.1] - 2020-09-27
### Added
* Added motor `torque_constant`: units of torque are now [Nm] instead of just motor current.
* Added `motor.config.torque_lim`: limit for motor torque in [Nm].
* [Motor thermistors support](docs/thermistors.md)
* Enable/disable of thermistor thermal limits according `setting axis.<thermistor>.enabled`.
* Introduced `odrive-interface.yaml` as a root source for the ODrive's API. `odrivetool` connects much faster as a side effect.
* Added torque_constant and torque_lim to motor config

### Changed
* **`input_pos`, `input_vel`, `pos_estimate_linear`, `pos_estimate_circular`, are now in units of [turns] or [turns/s] instead of [counts] or [counts/s]**
* **`pos_gain`, `vel_gain`, `vel_integrator_gain`, are now in units of [(turns/s) / turns], [Nm/(turns/s)], [Nm/(turns/s * s)] instead of [(counts/s) / counts], [A/(counts/s)], [A/((counts/s) * s)].** `pos_gain` is not affected. Old values of `vel_gain` and `vel_integrator_gain` should be multiplied by `torque_constant * encoder cpr` to convert from the old units to the new units. `torque_constant` is approximately equal to 8.27 / (motor KV).
* `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

### Fixed
* 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
## [0.5.0] - 2020-08-03
### Added
* AC Induction Motor support.
Expand Down
20 changes: 13 additions & 7 deletions Dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -7,16 +7,22 @@ RUN add-apt-repository ppa:team-gcc-arm-embedded/ppa
RUN add-apt-repository ppa:jonathonf/tup
RUN apt-get update
RUN apt-get -y upgrade
RUN apt-get -y install gcc-arm-embedded openocd tup python3.7 build-essential git
RUN apt-get -y install gcc-arm-embedded openocd tup python3.7 python3-yaml python3-jinja2 python3-jsonschema build-essential git

# Build step below does not know about debian's python naming schemme
RUN ln -s /usr/bin/python3.7 /usr/bin/python

# Copy the firmware tree into the container
RUN mkdir ODrive
COPY . ODrive
RUN mkdir -p ODrive
WORKDIR ODrive/Firmware

# Hack around Tup's dependency on FUSE
RUN tup generate build.sh
RUN ./build.sh
# Must attach the firmware tree into the container
CMD \
# Regenerate python interface
python interface_generator_stub.py \
--definitions odrive-interface.yaml \
--template ../tools/enums_template.j2 \
--output ../tools/odrive/enums.py && \
# Hack around Tup's dependency on FUSE
tup init && \
tup generate build.sh && \
./build.sh
8 changes: 8 additions & 0 deletions Firmware/Board/v3/Src/stm32f4xx_it.c
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,7 @@
#include "stm32f4xx.h"
#include "stm32f4xx_it.h"
#include "cmsis_os.h"
#include <stdbool.h>

/* USER CODE BEGIN 0 */
#include <Drivers/STM32/stm32_system.h>
Expand Down Expand Up @@ -88,6 +89,13 @@ void get_regs(void** stack_ptr) {
void* volatile pc __attribute__((unused)) = stack_ptr[6]; // Program counter
void* volatile psr __attribute__((unused)) = stack_ptr[7]; // Program status register

void* volatile cfsr __attribute__((unused)) = (void*)SCB->CFSR; // Configurable fault status register
void* volatile cpacr __attribute__((unused)) = (void*)SCB->CPACR;
void* volatile fpccr __attribute__((unused)) = (void*)FPU->FPCCR;

volatile bool preciserr __attribute__((unused)) = (uint32_t)cfsr & 0x200;
volatile bool ibuserr __attribute__((unused)) = (uint32_t)cfsr & 0x100;

volatile int stay_looping = 1;
while(stay_looping);
}
Expand Down
5 changes: 3 additions & 2 deletions Firmware/MotorControl/axis.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -189,9 +189,9 @@ bool Axis::do_checks() {
// controller_.do_checks();

// Check for endstop presses
if (min_endstop_.config_.enabled && min_endstop_.get_state() && !(current_state_ == AXIS_STATE_HOMING)) {
if (min_endstop_.config_.enabled && min_endstop_.rose() && !(current_state_ == AXIS_STATE_HOMING)) {
error_ |= ERROR_MIN_ENDSTOP_PRESSED;
} else if (max_endstop_.config_.enabled && max_endstop_.get_state() && !(current_state_ == AXIS_STATE_HOMING)) {
} else if (max_endstop_.config_.enabled && max_endstop_.rose() && !(current_state_ == AXIS_STATE_HOMING)) {
error_ |= ERROR_MAX_ENDSTOP_PRESSED;
}

Expand Down Expand Up @@ -410,6 +410,7 @@ bool Axis::run_homing() {
// Avoid integrator windup issues
controller_.vel_integrator_torque_ = 0.0f;

// Driving toward the endstop
run_control_loop([this](){
// Note that all estimators are updated in the loop prefix in run_control_loop
float torque_setpoint;
Expand Down
5 changes: 1 addition & 4 deletions Firmware/MotorControl/endstop.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@

void Endstop::update() {
debounceTimer_.update();
last_state_ = endstop_state_;
if (config_.enabled) {
bool last_pin_state = pin_state_;

Expand All @@ -19,10 +20,6 @@ void Endstop::update() {
}
}

bool Endstop::get_state() {
return endstop_state_;
}

bool Endstop::apply_config() {
debounceTimer_.reset();
if (config_.enabled) {
Expand Down
13 changes: 12 additions & 1 deletion Firmware/MotorControl/endstop.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,11 +26,22 @@ class Endstop {
bool apply_config();

void update();
bool get_state();
constexpr bool get_state(){
return endstop_state_;
}

constexpr bool rose(){
return (endstop_state_ != last_state_) && endstop_state_;
}

constexpr bool fell(){
return (endstop_state_ != last_state_) && !endstop_state_;
}

bool endstop_state_ = false;

private:
bool last_state_ = false;
bool pin_state_ = false;
float pos_when_pressed_ = 0.0f;
Timer<float> debounceTimer_;
Expand Down
2 changes: 1 addition & 1 deletion Firmware/MotorControl/low_level.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -380,7 +380,7 @@ void vbus_sense_adc_cb(ADC_HandleTypeDef* hadc, bool injected) {
}

// This is the callback from the ADC that we expect after the PWM has triggered an ADC conversion.
// TODO: Document how the phasing is done, link to timing diagram
// Timing diagram: Firmware/timing_diagram_v3.png
void pwm_trig_adc_cb(ADC_HandleTypeDef* hadc, bool injected) {
#define calib_tau 0.2f //@TOTO make more easily configurable
constexpr float calib_filter_k = CURRENT_MEAS_PERIOD / calib_tau;
Expand Down
30 changes: 29 additions & 1 deletion Firmware/communication/ascii_protocol.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@ void cmd_read_property(char * pStr, StreamSink& response_channel, bool use_check
void cmd_write_property(char * pStr, StreamSink& response_channel, bool use_checksum);
void cmd_update_axis_wdg(char * pStr, StreamSink& response_channel, bool use_checksum);
void cmd_unknown(char * pStr, StreamSink& response_channel, bool use_checksum);
void cmd_encoder(char * pStr, StreamSink& response_channel, bool use_checksum);

/* Function implementations --------------------------------------------------*/

Expand Down Expand Up @@ -122,6 +123,7 @@ void ASCII_protocol_process_line(const uint8_t* buffer, size_t len, StreamSink&
case 'r': cmd_read_property(cmd, response_channel, use_checksum); break; // read property
case 'w': cmd_write_property(cmd, response_channel, use_checksum); break; // write property
case 'u': cmd_update_axis_wdg(cmd, response_channel, use_checksum); break; // Update axis watchdog.
case 'e': cmd_encoder(cmd, response_channel, use_checksum); break; // Encoder commands
default : cmd_unknown(nullptr, response_channel, use_checksum); break;
}
}
Expand Down Expand Up @@ -220,11 +222,37 @@ void cmd_set_torque(char * pStr, StreamSink& response_channel, bool use_checksum
}
}

// @brief Sets the encoder linear count
// @param pStr buffer of ASCII encoded values
// @param response_channel reference to the stream to respond on
// @param use_checksum bool to indicate whether a checksum is required on response
void cmd_encoder(char * pStr, StreamSink& response_channel, bool use_checksum) {
if (pStr[1] == 's') {
pStr += 2; // Substring two characters to the right (ok because we have guaranteed null termination after all chars)

unsigned motor_number;
int encoder_count;

if (sscanf(pStr, "l %u %i", &motor_number, &encoder_count) < 2) {
respond(response_channel, use_checksum, "invalid command format");
} else if (motor_number >= AXIS_COUNT) {
respond(response_channel, use_checksum, "invalid motor %u", motor_number);
} else {
Axis& axis = axes[motor_number];
axis.encoder_.set_linear_count(encoder_count);
axis.watchdog_feed();
respond(response_channel, use_checksum, "encoder set to %u", encoder_count);
}
} else {
respond(response_channel, use_checksum, "invalid command format");
}
}

// @brief Executes the set trapezoid trajectory command
// @param pStr buffer of ASCII encoded values
// @param response_channel reference to the stream to respond on
// @param use_checksum bool to indicate whether a checksum is required on response
void cmd_set_trapezoid_trajectory(char * pStr, StreamSink& response_channel, bool use_checksum) {
void cmd_set_trapezoid_trajectory(char* pStr, StreamSink& response_channel, bool use_checksum) {
unsigned motor_number;
float goal_point;

Expand Down
6 changes: 5 additions & 1 deletion Firmware/communication/can_simple.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -382,6 +382,10 @@ void CANSimple::clear_errors_callback(Axis* axis, can_Message_t& msg) {
axis->clear_errors();
}

void CANSimple::set_linear_count_callback(Axis* axis, can_Message_t& msg){
axis->encoder_.set_linear_count(can_getSignal<int32_t>(msg, 0, 32, true));
}

void CANSimple::send_heartbeat(Axis* axis) {
can_Message_t txmsg;
txmsg.id = axis->config_.can_node_id << NUM_CMD_ID_BITS;
Expand Down Expand Up @@ -409,4 +413,4 @@ uint32_t CANSimple::get_node_id(uint32_t msgID) {

uint8_t CANSimple::get_cmd_id(uint32_t msgID) {
return (msgID & 0x01F); // Bottom 5 bits
}
}
1 change: 1 addition & 0 deletions Firmware/communication/can_simple.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,6 +62,7 @@ class CANSimple {
static void get_sensorless_estimates_callback(Axis* axis, can_Message_t& msg);
static void get_vbus_voltage_callback(Axis* axis, can_Message_t& msg);
static void clear_errors_callback(Axis* axis, can_Message_t& msg);
static void set_linear_count_callback(Axis* axis, can_Message_t& msg);

// Utility functions
static uint32_t get_node_id(uint32_t msgID);
Expand Down
Loading

0 comments on commit d6debf8

Please sign in to comment.