AS5048A with Mks dual foc v3.3 and GM6208-150T Gimbal Motor

Having satisfactorily gotten my GM6208 to work in Open loop mode: Open loop velocity control not working at low velocity

I want to add the AS0548A I have but I am confused about how to connect it.

From what I have read I should be using SPI rather than PWM, due to better performance and I believe I should be using this library: Arduino-FOC-drivers/src/encoders/as5048a at master · simplefoc/Arduino-FOC-drivers · GitHub

I have an Mks dual foc v3.3 with the included ESP32 that is soldered to the driver board using the supplied risers.

Makerbase have a closed loop velocity example: MKS-DUALFOC/Test Code/4_close_loop_velocity_example/4_close_loop_velocity_example.ino at main · makerbase-motor/MKS-DUALFOC · GitHub in which it appears to me they are using pins 19 & 18 and 23 & 5 for each motor’s SDA and SLC:|

...
MagneticSensorI2C sensor = MagneticSensorI2C(AS5600_I2C);
MagneticSensorI2C sensor1 = MagneticSensorI2C(AS5600_I2C);
TwoWire I2Cone = TwoWire(0);
TwoWire I2Ctwo = TwoWire(1);
...
void setup() {
  I2Cone.begin(19, 18, 400000); 
  I2Ctwo.begin(23, 5, 400000);
  sensor.init(&I2Cone); 
  sensor1.init(&I2Ctwo);
  //Connect the motor object with the sensor object
  motor.linkSensor(&sensor);
  motor1.linkSensor(&sensor1);
...}

Great - but what I can’t figure out is which connections from the AS5048A are SDA and SLC.

I guess if I actually understood what SDA and SLC are I might be able to make an educated guess, but I would prefer to understand this.

I assume I would need to connect ground, and 5V (can I use 3.3V?) but which of nCS, CLK, MOSI, and MISO equate to SDA and SLC?

Sorry - my ignorance is once again showing.

Yes, AS5048A will work with 3.3V.

Looking at an ESP32 pinout, it looks like 23 is MOSI, 19 is MISO, 18 is SCK, and 5 is CS. So since the example code is using those pins for I2C, that likely means the four pins labeled SDA and SCL on the Dual FOC are connected to those ESP32 pins, and it’s just a matter of sorting out which is which with a multimeter.

The real question is how they’re able to use those pins for I2C :slight_smile: The ESP32 pinout looks like it only has one I2C interface on pins 21 and 22.

Thanks for that, with your suggestion I have determined (I think) which pins on the DualFOC header pins go to which pins on the ESP32.

I wired up a harness for it:

And it gets plugged in here:

I have continuity between the soldered pads on the AS5048A and the GPIO pins on the ESP32 for all 6 lines using this as a reference: ESP32 Pinout Reference - Last Minute Engineers

According to this: Magnetic sensor SPI | Arduino-FOC I believe I should:

  1. create an instance of the MagneticSensorSPI class. I used GPIO5 for chip_select, I can confirm continuity between the AS5048A nCS solder pad and GPIO5 on the ESP32:
MagneticSensorSPI sensor = MagneticSensorSPI(5, 14, 0x3FFF);
  1. Initialize and link the sensor:
// init magnetic sensor hardware
  sensor.init();
  motor.linkSensor(&sensor);
  1. Initialize and link the driver:
// driver
  driver.init()
  motor.linkDriver(&driver);
  1. Initialize the motor:
// init motor hardware
  motor.init();
  motor.initFOC();

  1. call loopFOC() and move() in the main loop:
void loop(){
  motor.loopFOC();
  motor.move();

So I loaded the closed loop example full_control_serial from the Arduino examples, modified for my motor and sensor:

/**
 * Comprehensive BLDC motor control example using magnetic sensor
 *
 * Using serial terminal user can send motor commands and configure the motor and FOC in real-time:
 * - configure PID controller constants
 * - change motion control loops
 * - monitor motor variabels
 * - set target values
 * - check all the configuration values
 *
 * See more info in docs.simplefoc.com/commander_interface
 */
#include <SimpleFOC.h>

// magnetic sensor instance - SPI
MagneticSensorSPI sensor = MagneticSensorSPI(5, 14, 0x3FFF);

// BLDC motor & driver instance
BLDCMotor motor = BLDCMotor(14);
BLDCDriver3PWM driver = BLDCDriver3PWM(32,33,25,22);    

// commander interface
Commander command = Commander(Serial);
void onMotor(char* cmd){ command.motor(&motor, cmd); }

void setup() {

  // use monitoring with serial 
  Serial.begin(115200);
  // enable more verbose output for debugging
  // comment out if not needed
  SimpleFOCDebug::enable(&Serial);

  // initialise magnetic sensor hardware
  sensor.init();
  // link the motor to the sensor
  motor.linkSensor(&sensor);

  // driver config
  // power supply voltage [V]
  driver.voltage_power_supply = 12;
  driver.init();
  // link driver
  motor.linkDriver(&driver);

  // choose FOC modulation
  motor.foc_modulation = FOCModulationType::SpaceVectorPWM;

  // set control loop type to be used
  motor.controller = MotionControlType::torque;

  // contoller configuration based on the control type
  motor.PID_velocity.P = 0.2f;
  motor.PID_velocity.I = 20;
  motor.PID_velocity.D = 0;
  // default voltage_power_supply
  motor.voltage_limit = 12;

  // velocity low pass filtering time constant
  motor.LPF_velocity.Tf = 0.01f;

  // angle loop controller
  motor.P_angle.P = 20;
  // angle loop velocity limit
  motor.velocity_limit = 50;

  // comment out if not needed
  motor.useMonitoring(Serial);

  // initialise motor
  motor.init();
  // align encoder and start FOC
  motor.initFOC();

  // set the inital target value
  motor.target = 2;

  // define the motor id
  command.add('A', onMotor, "motor");

  // Run user commands to configure and the motor (find the full command list in docs.simplefoc.com)
  Serial.println(F("Motor commands sketch | Initial motion control > torque/voltage : target 2V."));

  _delay(1000);
}


void loop() {
  // iterative setting FOC phase voltage
  motor.loopFOC();

  // iterative function setting the outter loop target
  // velocity, position or voltage
  // if tatget not set in parameter uses motor.target variable
  motor.move();

  // user communication
  command.run();
}

The driver board has a 5V out which I pass to the ESP32 so it is powered when no serial cable is connected to the PC:

If I leave the power connection from the Driver board to the ESP32 I am getting this in the serial monitor on a reset:

rst:0x1 (POWERON_RESET),boot:0x1b (SPI_FAST_FLASH_BOOT)
configsip: 0, SPIWP:0xee
clk_drv:0x00,q_drv:0x00,d_drv:0x00,cs0_drv:0x00,hd_drv:0x00,wp_drv:0x00
mode:DIO, clock div:1
load:0x3fff0030,len:4916
load:0x40078000,len:16436
load:0x40080400,len:4
ho 8 tail 4 room 4
load:0x40080404,len:3524
entry 0x400805b8
ESP32-DRV: Configuring 3PWM in group: 0 on timer: 0
ESP32-DRV: Configuring 2 operators.
ESP32-DRV: Configuring 3 comparators.
ESP32-DRV: Configuring 3 generators.
ESP32-DRV: Configuring center-aligned pwm.
ESP32-DRV: Enabling timer: 0
ESP32-DRV: MCPWM configured!
MOT: Monitor enabled!
MOT: Init
MOT: Enable driver.
MOT: Align sensor.
MOT: Failed to notice movement
MOT: Init FOC failed.
Motor commands sketch | Initial motion control > torque/voltage : target 20V.

If I disconnect the power leaving only the USB serial 5V I get this on reset:

rst:0x1 (POWERON_RESET),boot:0x1b (SPI_FAST_FLASH_BOOT)
configsip: 0, SPIWP:0xee
clk_drv:0x00,q_drv:0x00,d_drv:0x00,cs0_drv:0x00,hd_drv:0x00,wp_drv:0x00
mode:DIO, clock div:1
load:0x3fff0030,len:4916
load:0x40078000,len:16436
load:0x40080400,len:4
ho 8 tail 4 room 4
load:0x40080404,len:3524
entry 0x400805b8
ESP32-DRV: Configuring 3PWM in group: 0 on timer: 0
ESP32-DRV: Configuring 2 operators.
ESP32-DRV: Configuring 3 comparators.
ESP32-DRV: Configuring 3 generators.
ESP32-DRV: Configuring center-aligned pwm.
ESP32-DRV: Enabling timer: 0
ESP32-DRV: MCPWM configured!
MOT: Monitor enabled!
MOT: Init
MOT: Enable driver.
MOT: Align sensor.
MOT: sensor_direction==CW
MOT: PP check: fail - estimated pp: 0.97
MOT: Zero elec. angle: 1.18
MOT: No current sense.
MOT: Ready.
Motor commands sketch | Initial motion control > torque/voltage : target 20V.

What is:

MOT: PP check: fail - estimated pp: 0.97
MOT: Zero elec. angle: 1.18

I had expected after this to be able to enter commander commands at the serial console and be able to control the motor but I cannot.

I appear to be flailing…

Any suggestions? I am really struggling to get this motor to run in a closed loop.

Try MagneticSensorSPI sensor(AS5048_SPI, 5);
I haven’t used any SPI sensors myself, but I assume if there’s a special configuration for it then it probably needs some non-default settings.

EDIT: Or better yet, that even more specialized class in the drivers repository that you linked in the original post.

Hi there!

I have also recently got a MKS DualFOC V3.3 for a self balancing robot I’m working on and have had it working with AS5048A encoders over SPI but I am not using the Lolin32 Lite board and have instead been using an ESP32-S3 Devboard currently but I have been designing a PCB as a drop in replacement for the Lolin board.

The board is currently being shipped to me so I haven’t been able to test as of yet but it breaks out 4 SPI connections as well as whatever GPIO are spare to the pins on the DualFOC.

After I have been able to test, I can share the design files if you like.

EDIT: Why are you powering the ESP32 whilst also connecting it to the DualFOC? The DualFOC supplies 3.3V directly to the ESP32 3.3V pin using the pin sockets so you’re probably having brownout or voltage issues causing your current sense errors.

Thanks both of you guys.

MagneticSensorSPI sensor(AS5048_SPI, 5);

@dekutree64 thanks for that. No change unfortunately.

@claw_ntl

Because I am a bit ignorant and trying to figuring this out I guess. I couldn’t find much documentation that I could really understand, some of it going over my head.

This stuff is relatively new to me, and I have a lot to learn.

Which wires from the AS5048A did you use may I ask? Do you have any suggestions for what I am missing?

I would definitely be very interested in hearing how that board goes too.

Some documentation, schematics and examples can be found here: https://github.com/makerbase-motor/MKS-DUALFOC

I am using the MISO, MOSI, CLK and CS pins on the AS5048A for 4 Wire SPI communication (also note the AS5048A does not support I2C). I recommend using the SimpleFOC Drivers library for the AS5048A (https://github.com/simplefoc/Arduino-FOC-drivers/tree/master/src/encoders/as5048a).You will probably need to initialise the SPI bus for it to work. See the code I have written below as reference but just check the pin definitions:

#include <Arduino.h>

#include <SPI.h>

// SimpleFOC
#include <SimpleFOC.h>
#include <SimpleFOCDrivers.h>
#include "encoders/as5048a/MagneticSensorAS5048A.h"

// Change these to suit the pins you use
#define HSPI_MOSI     23
#define HSPI_MISO     19
#define HSPI_SCK      18
#define CS_ENC_A      5
#define CS_ENC_B      -1

// Setup a pointer for the SPI class
SPIClass *hspi = NULL;

// SPI Clock Speed - AS5048A support 10 MHz maximum
static const uint32_t AS5048A_spiClk = 1000000UL;  // 1 MHz

// Create sensor instances
MagneticSensorAS5048A sensorA(CS_ENC_A, false, SPISettings(AS5048A_spiClk, MSBFIRST, SPI_MODE1));
MagneticSensorAS5048A sensorB(CS_ENC_B, false, SPISettings(AS5048A_spiClk, MSBFIRST, SPI_MODE1));

void setup() {
	
	// Create hspi instance
	hspi = new SPIClass(HSPI); // Original ESP32 has HSPI and VSPI available for use
	hspi->begin(HSPI_SCK, HSPI_MISO, HSPI_MOSI); // Assign the pins
  
	// Assign the SPI bus to the the sensors
	sensorA.init(hspi);
	sensorB.init(hspi);
}

The bare PCB should be delivered this week so should be able to test soon.