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

Fixes before release 2.3.1 #304

Merged
merged 8 commits into from
Sep 21, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 3 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -30,8 +30,9 @@ Therefore this is an attempt to:
> - Expose I2C errors in MagneticSensorI2C (thanks to [@padok](https://github.com/padok))
> - Improved default trig functions (sine, cosine) - faster, smaller
> - Overridable trig functions - plug in your own optimized versions
> - bugfix: microseconds overflow in velocity mode
> - bugfix: KV initialization
> - Bugfix: microseconds overflow in velocity mode
> - Bugfix: KV initialization
> - Compatibility with newest versions of Arduino framework for STM32, Renesas, ESP32, Atmel SAM, Atmel AVR, nRF52 and RP2040

## Arduino *SimpleFOClibrary* v2.3.1

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -62,6 +62,7 @@ void setup() {
void loop() {
// open loop angle movements
// using motor.voltage_limit and motor.velocity_limit
// angles can be positive or negative, negative angles correspond to opposite motor direction
motor.move(target_position);

// user communication
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,7 @@ void loop() {

// open loop velocity movement
// using motor.voltage_limit and motor.velocity_limit
// to turn the motor "backwards", just set a negative target_velocity
motor.move(target_velocity);

// user communication
Expand Down
1 change: 1 addition & 0 deletions src/common/foc_utils.h
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
#define _sqrt(a) (_sqrtApprox(a))
#define _isset(a) ( (a) != (NOT_SET) )
#define _UNUSED(v) (void) (v)
#define _powtwo(x) (1 << (x))

// utility defines
#define _2_SQRT3 1.15470053838f
Expand Down
2 changes: 2 additions & 0 deletions src/current_sense/GenericCurrentSense.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,6 +62,8 @@ int GenericCurrentSense::driverAlign(float voltage){
int exit_flag = 1;
if(skip_align) return exit_flag;

if (!initialized) return 0;

// // set phase A active and phases B and C down
// driver->setPwm(voltage, 0, 0);
// _delay(200);
Expand Down
8 changes: 8 additions & 0 deletions src/current_sense/InlineCurrentSense.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
#include "InlineCurrentSense.h"
#include "communication/SimpleFOCDebug.h"
// InlineCurrentSensor constructor
// - shunt_resistor - shunt resistor value
// - gain - current-sense op-amp gain
Expand Down Expand Up @@ -93,6 +94,13 @@ int InlineCurrentSense::driverAlign(float voltage){
int exit_flag = 1;
if(skip_align) return exit_flag;

if (driver==nullptr) {
SIMPLEFOC_DEBUG("CUR: No driver linked!");
return 0;
}

if (!initialized) return 0;

if(_isset(pinA)){
// set phase A active and phases B and C down
driver->setPwm(voltage, 0, 0);
Expand Down
11 changes: 10 additions & 1 deletion src/current_sense/LowsideCurrentSense.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
#include "LowsideCurrentSense.h"
#include "communication/SimpleFOCDebug.h"
// LowsideCurrentSensor constructor
// - shunt_resistor - shunt resistor value
// - gain - current-sense op-amp gain
Expand Down Expand Up @@ -35,6 +36,12 @@ LowsideCurrentSense::LowsideCurrentSense(float _mVpA, int _pinA, int _pinB, int

// Lowside sensor init function
int LowsideCurrentSense::init(){

if (driver==nullptr) {
SIMPLEFOC_DEBUG("CUR: Driver not linked!");
return 0;
}

// configure ADC variables
params = _configureADCLowSide(driver->params,pinA,pinB,pinC);
// if init failed return fail
Expand Down Expand Up @@ -89,10 +96,12 @@ PhaseCurrent_s LowsideCurrentSense::getPhaseCurrents(){
// 3 - success but gains inverted
// 4 - success but pins reconfigured and gains inverted
int LowsideCurrentSense::driverAlign(float voltage){

int exit_flag = 1;
if(skip_align) return exit_flag;

if (!initialized) return 0;

if(_isset(pinA)){
// set phase A active and phases B and C down
driver->setPwm(voltage, 0, 0);
Expand Down
3 changes: 3 additions & 0 deletions src/current_sense/hardware_specific/rp2040/rp2040_mcu.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@ float _readADCVoltageInline(const int pinA, const void* cs_params) {
// return readings from the same ADC conversion run. The ADC on RP2040 is anyway in round robin mode :-(
// like this we either have to block interrupts, or of course have the chance of reading across
// new ADC conversions, which probably won't improve the accuracy.
_UNUSED(cs_params);

if (pinA>=26 && pinA<=29 && engine.channelsEnabled[pinA-26]) {
return engine.lastResults.raw[pinA-26]*engine.adc_conv;
Expand All @@ -36,6 +37,8 @@ float _readADCVoltageInline(const int pinA, const void* cs_params) {


void* _configureADCInline(const void *driver_params, const int pinA, const int pinB, const int pinC) {
_UNUSED(driver_params);

if( _isset(pinA) )
engine.addPin(pinA);
if( _isset(pinB) )
Expand Down
13 changes: 12 additions & 1 deletion src/drivers/hardware_specific/renesas/renesas.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,8 @@
#include "communication/SimpleFOCDebug.h"
#include "FspTimer.h"

#define GPT_OPEN (0x00475054ULL)

/*
We use the GPT timers, there are 2 channels (32 bit) + 6 channels (16 bit)
Each channel has 2 outputs (GTIOCAx and GTIOCBx) which can be complimentary.
Expand Down Expand Up @@ -202,6 +204,7 @@ bool configureTimerPin(RenesasHardwareDriverParams* params, uint8_t index, bool
t->timer_cfg.p_context = nullptr;
t->timer_cfg.p_extend = &(t->ext_cfg);
t->timer_cfg.cycle_end_ipl = BSP_IRQ_DISABLED;
t->timer_cfg.cycle_end_irq = FSP_INVALID_VECTOR;

t->ext_cfg.p_pwm_cfg = &(t->pwm_cfg);
t->pwm_cfg.trough_ipl = BSP_IRQ_DISABLED;
Expand Down Expand Up @@ -256,6 +259,14 @@ bool configureTimerPin(RenesasHardwareDriverParams* params, uint8_t index, bool
t->ext_cfg.gtior_setting.gtior_b.obdflt = active_high ? 0x00 : 0x01;
}

// lets stop the timer in case its running
if (GPT_OPEN == t->ctrl.open) {
if (R_GPT_Stop(&(t->ctrl)) != FSP_SUCCESS) {
SIMPLEFOC_DEBUG("DRV: timer stop failed");
return false;
}
}

memset(&(t->ctrl), 0, sizeof(gpt_instance_ctrl_t));
err = R_GPT_Open(&(t->ctrl),&(t->timer_cfg));
if ((err != FSP_ERR_ALREADY_OPEN) && (err != FSP_SUCCESS)) {
Expand Down Expand Up @@ -294,7 +305,7 @@ bool configureTimerPin(RenesasHardwareDriverParams* params, uint8_t index, bool
bool startTimerChannels(RenesasHardwareDriverParams* params, int num_channels) {
uint32_t mask = 0;
for (int i = 0; i < num_channels; i++) {
RenesasTimerConfig* t = params->timer_config[i];
// RenesasTimerConfig* t = params->timer_config[i];
// if (R_GPT_Start(&(t->ctrl)) != FSP_SUCCESS) {
// SIMPLEFOC_DEBUG("DRV: timer start failed");
// return false;
Expand Down
4 changes: 2 additions & 2 deletions src/sensors/MagneticSensorI2C.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ MagneticSensorI2C::MagneticSensorI2C(uint8_t _chip_address, int _bit_resolution,
// angle read register of the magnetic sensor
angle_register_msb = _angle_register_msb;
// register maximum value (counts per revolution)
cpr = pow(2, _bit_resolution);
cpr = _powtwo(_bit_resolution);

// depending on the sensor architecture there are different combinations of
// LSB and MSB register used bits
Expand All @@ -48,7 +48,7 @@ MagneticSensorI2C::MagneticSensorI2C(MagneticSensorI2CConfig_s config){
// angle read register of the magnetic sensor
angle_register_msb = config.angle_register;
// register maximum value (counts per revolution)
cpr = pow(2, config.bit_resolution);
cpr = _powtwo(config.bit_resolution);

int bits_used_msb = config.data_start_bit - 7;
lsb_used = config.bit_resolution - bits_used_msb;
Expand Down
6 changes: 3 additions & 3 deletions src/sensors/MagneticSensorSPI.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,13 +31,13 @@ MagneticSensorSPIConfig_s MA730_SPI = {
// cs - SPI chip select pin
// _bit_resolution sensor resolution bit number
// _angle_register - (optional) angle read register - default 0x3FFF
MagneticSensorSPI::MagneticSensorSPI(int cs, float _bit_resolution, int _angle_register){
MagneticSensorSPI::MagneticSensorSPI(int cs, int _bit_resolution, int _angle_register){

chip_select_pin = cs;
// angle read register of the magnetic sensor
angle_register = _angle_register ? _angle_register : DEF_ANGLE_REGISTER;
// register maximum value (counts per revolution)
cpr = pow(2,_bit_resolution);
cpr = _powtwo(_bit_resolution);
spi_mode = SPI_MODE1;
clock_speed = 1000000;
bit_resolution = _bit_resolution;
Expand All @@ -52,7 +52,7 @@ MagneticSensorSPI::MagneticSensorSPI(MagneticSensorSPIConfig_s config, int cs){
// angle read register of the magnetic sensor
angle_register = config.angle_register ? config.angle_register : DEF_ANGLE_REGISTER;
// register maximum value (counts per revolution)
cpr = pow(2, config.bit_resolution);
cpr = _powtwo(config.bit_resolution);
spi_mode = config.spi_mode;
clock_speed = config.clock_speed;
bit_resolution = config.bit_resolution;
Expand Down
2 changes: 1 addition & 1 deletion src/sensors/MagneticSensorSPI.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ class MagneticSensorSPI: public Sensor{
* @param bit_resolution sensor resolution bit number
* @param angle_register (optional) angle read register - default 0x3FFF
*/
MagneticSensorSPI(int cs, float bit_resolution, int angle_register = 0);
MagneticSensorSPI(int cs, int bit_resolution, int angle_register = 0);
/**
* MagneticSensorSPI class constructor
* @param config SPI config
Expand Down