B-G431B-ESC1 Rev C (MB1419C) confirmation needed on shunt resistance & current sense gain for foc_current mode

Hi all,

Update on my reaction wheel ACS project (3-DOF CubeSat attitude control, V4008 380KV outrunners, AS5600 sensors on shared I2C). Last time I was here I was sourcing diametric magnets (the modules I’d bought shipped with axial magnets despite being sold as AS5600 kits). That’s resolved; sensor is reading clean angles nowww~

The new problem I’m facing:

In torque / foc_current mode, the motor twitches but won’t start from rest. If I help it spin by hand it can sustain rotation for a while and then it stops abruptly, but it can’t initiate motion.

I added phase-current logging to the loop. With target = -0.80 A commanded, the measured phase currents are bouncing around ±0.1 A (should be ~0 by Kirchhoff). So the inner current PID is seeing noise rather than tracking commanded current.

Things I’ve triedd:

  • motor.voltage_sensor_align = 3 and 5; gets past alignment

  • currentSense.skip_align = true; alignment passes but operation fails the same way

  • motor.LPF_velocity.Tf = 0.01; improved velocity noise (was ±2 rad/s, now ±0.5)

  • LPF_current_q/d.Tf raised to 0.01; no improvement on current sense behavior

I think my current sense parameters are wrong for my specific board revision. My firmware has:

LowsideCurrentSense currentSense = LowsideCurrentSense(
  0.003f,        // shunt resistance
  -64.0f / 7.0f, // amp gain
  A_OP1_OUT, A_OP2_OUT, A_OP3_OUT
);

These are values I picked up from an example sketch online.
But I just checked the silkscreen and confirmed I have MB1419 Rev C. The three shunt resistors near OUT1/OUT2/OUT3 are physically large copper-block SMDs. I can’t read a value marking on them from my angle.

My questionnn

Has anyone got foc_current working reliably on Rev C (MB1419C) specifically? If so, what shunt resistance and op-amp gain factor did you use?

  1. Are there silkscreen markings on the shunt resistors themselves I should be looking for? Or is there a way to look up the BOM for Rev C?

  2. Is there a programmatic sanity check I can add inside the firmware to assert the current sense calibration looks right before initFOC runs?

I’ve checked the SimpleFOC docs and skimmed the forum but most posts I’ve found are for Rev A. Would really appreciate confirmation from anyone with the same board.

Why this matters to meee:

This is my final year project and I have give or take 3 weeks until defense and a working three-axis hardware demo is non-negotiable.

The simulation is built around foc_current, I feel like falling back to voltage mode would weaken the thesis claim significantly. So I’m trying hard to keep the current-control architecture.

Thanks in advance this community has unblocked me multiple times already, i probably owe half my projects progress to yalll T_T

4 Answers

4

Thankfully I had considered selling mine a couple years ago and took photos, so I could easily check that they are MB1419C


They work with those numbers, and the readings are good quality (plenty of resolution, low noise), so you should be able to get it working.

Not sure what to suggest for debugging since mine were unusually easy to set up just using the default current PID settings. Post your whole code and I’ll see if I can spot anything.

Can’t help you with the current sense problem, other then recommending to check out the calibrated_sensor , just in case your magnets are not perfect.

What triggered me to post here?

@dekutree64
Thank youu, really appreciate the responsee! T_T confirmation that MB1419C works with the same shunt/gain I have is hugee, narrows the search significantly for mee

Posting my full setup and the path that got me here in case it helps anyone
spot what I’m missing.

This is for a single motor on the bench, not yet integrated with the ESP32 —
I’m running per-axis bring-up first, sending T commands over serial via commander.

Where the code started:

Initial firmware was the standard SimpleFOC torque/foc_current template, with
ZERO_ELEC_ANGLE and SENSOR_DIR left at NOT_SET / UNKNOWN so the first boot
runs alignment, then I’d paste those values back to skip alignment on
subsequent boots.

Shunt and gain were the values I’d seen in example sketches
(0.003 Ω, -64/7 gain). Default current PID values (P=3, I=100, D=0). Default
filters (LPF_current_q/d.Tf = 0.005). 25 kHz PWM, SpaceVectorPWM modulation.

Changes I made (all the deets):

  1. After fixing wiring fully, and trying the newer sensor, FOC aligned cleanly:
    zero_electric_angle = 4.221518
    sensor_direction = -1 (CCW)
    Baked these into the firmware as #defines so subsequent boots skip
    alignment; since the wheel won’t be free to spin once the
    cube is assembled

  2. With sensor calibration baked in, alignment progressed to Align current
    sense and failed with CS: Err too low current, rise voltage!
    Added motor.voltage_sensor_align = 3 (then later 5) alignment now
    succeeds with Success: 1.

  3. Commented out the watchdog for bench testing. Without the watchdog, motor still doesn’t rotate from rest, I’d sometimes give it a nudge and it’d start then abruptly stop; sometimes it’d not rotate at all regardless of whichever command I gave :frowning:
    This is when I added diagnostic phase current logging at 5 Hz to see
    what current sense was actually reading.

Current output:

At idle (target = 0.00):
target=0.00  vel=-0.1  i_a=0.060  i_b=0.070  i_c=-0.038  sum=0.092
target=0.00  vel=1.0   i_a=-0.028 i_b=0.070  i_c=0.021   sum=0.062
target=0.00  vel=2.3   i_a=0.003  i_b=0.015  i_c=-0.038  sum=-0.020

With target = -0.80:
target=-0.80  vel=-0.5  i_a=0.089  i_b=0.070  i_c=-0.009  sum=0.151
target=-0.80  vel=-2.0  i_a=0.001  i_b=0.041  i_c=-0.009  sum=0.033
target=-0.80  vel=-1.1  i_a=-0.028 i_b=-0.018 i_c=-0.009  sum=-0.055

Motor doesn’t spin; measured currents don’t track the -0.8A target, they look essentially same to the idle noise and the currents jitter ±0.1A, sum drifts ±0.2A instead of near zero, velocity reads ±2 rad/s noise when rotor is physically stationary :confused:

Workarounds I tried:

  1. currentSense.skip_align = true ; alignment passes, operation unchanged, reverted this auto-align is probably better :")
  2. motor.LPF_velocity.Tf = 0.01 added a 10ms low-pass on velocity readings to smooth the ±2 rad/s noise into something usable. Helped velocity readings (now ±0.5 rad/s at rest) but didn’t affect the foc_current behaviour obv.
  3. Raised motor.LPF_current_q.Tf and LPF_current_d.Tf from 0.005 to 0.01; no visible improvement on current sense readings.
  4. Like I said before, if I help the motor spin by hand while target = -0.8A, it then sustains rotation. It just can’t initiate motion from rest. Feels like the loop wakes up once there’s back-EMF to work with, but can’t push out of the cogging detents from standstill.

Things I haven’t tried (yet)

  1. Adjusting inner current PID gains away from the defaults (Pq=Pd=3,
    Iq=Id=100). Defaults worked so I don’t think this is it.
  2. CalibratedSensor (@o_lampe suggested this as a magnet-imperfection fix; my magnet seems fine in sensor-only testing but I haven’t characterised it rigorously).
  3. Lowering PWM frequency or trying different FOCModulationType.

Full firmware:

#include <SimpleFOC.h>

#define POLE_PAIRS    12

#define VBUS          14.8f

#define I_MAX         3.0f

#define V_LIMIT       VBUS

#define PWM_FREQ      25000

#define ZERO_ELEC_ANGLE   4.221518f

#define SENSOR_DIR        Direction::CCW


MagneticSensorI2C sensor = MagneticSensorI2C(AS5600_I2C);

BLDCMotor motor = BLDCMotor(POLE_PAIRS);

BLDCDriver6PWM driver = BLDCDriver6PWM(

  A_PHASE_UH, A_PHASE_UL,

  A_PHASE_VH, A_PHASE_VL,

  A_PHASE_WH, A_PHASE_WL

);

LowsideCurrentSense currentSense = LowsideCurrentSense(

  0.003f,

  -64.0f / 7.0f,

  A_OP1_OUT, A_OP2_OUT, A_OP3_OUT

);

Commander command(Serial);

unsigned long last_cmd_ms = 0;

void onTarget(char* cmd) {

  command.scalar(&motor.target, cmd);

  last_cmd_ms = millis();

}

void onMotor(char* cmd) {

  command.motor(&motor, cmd);

  last_cmd_ms = millis();

}

void setup() {

  Serial.begin(115200);

  Wire.setSDA(PB7);

  Wire.setSCL(PB8);

  Wire.setClock(400000);

  Wire.begin();

  delay(200);

  Serial.println("\n=== ACS ESC (debug v2) ===");

  sensor.init();

  motor.linkSensor(&sensor);

  driver.voltage_power_supply = VBUS;

  driver.voltage_limit        = V_LIMIT;

  driver.pwm_frequency        = PWM_FREQ;

  if (!driver.init()) {

    Serial.println("ERR: driver.init failed"); while (1) delay(100);

  }

  motor.linkDriver(&driver);

  currentSense.linkDriver(&driver);

  if (!currentSense.init()) {

    Serial.println("ERR: currentSense.init failed"); while (1) delay(100);

  }


  motor.linkCurrentSense(&currentSense);

  motor.LPF_velocity.Tf = 0.01f;

  motor.voltage_limit  = V_LIMIT;

  motor.current_limit  = I_MAX;

  motor.velocity_limit = 500.0f;

  // Inner FOC current PIDs

  motor.PID_current_q.P = 3.0f;

  motor.PID_current_q.I = 100.0f;

  motor.PID_current_q.D = 0.0f;

  motor.PID_current_q.limit       = V_LIMIT;

  motor.PID_current_q.output_ramp = 1000.0f;

  motor.LPF_current_q.Tf = 0.01f;          // was 0.005

  motor.PID_current_d.P = 3.0f;

  motor.PID_current_d.I = 100.0f;

  motor.PID_current_d.D = 0.0f;

  motor.PID_current_d.limit       = V_LIMIT;

  motor.PID_current_d.output_ramp = 1000.0f;

  motor.LPF_current_d.Tf = 0.01f;          // was 0.005 — more filtering

  motor.controller        = MotionControlType::torque;

  motor.torque_controller = TorqueControlType::foc_current;

  motor.foc_modulation    = FOCModulationType::SpaceVectorPWM;

  if (ZERO_ELEC_ANGLE != NOT_SET && SENSOR_DIR != Direction::UNKNOWN) {

    motor.zero_electric_angle = ZERO_ELEC_ANGLE;

    motor.sensor_direction    = SENSOR_DIR;

  }

  motor.voltage_sensor_align = 5;

  motor.useMonitoring(Serial);

  motor.monitor_downsample = 0;

  motor.init();

  if (!motor.initFOC()) {

    Serial.println("ERR: initFOC failed.");

    while (1) delay(100);

  }

  Serial.println("FOC aligned.");

  Serial.print("  zero_electric_angle = "); Serial.println(motor.zero_electric_angle, 6);

  Serial.print("  sensor_direction    = "); Serial.println((int)motor.sensor_direction);

  command.add('T', onTarget, "i_q target [A]");

  command.add('M', onMotor,  "motor command");

  motor.target = 0;

  last_cmd_ms  = millis();

  Serial.println("Ready. Send T<x> for current setpoint in Amps.");

}

void loop() {

  motor.loopFOC();

  motor.move();

  command.run();  // Watchdog DISABLED for bench testing
  // (will re-enable for final operation when ESP32 is the host)


  if (fabs(motor.shaft_velocity) > 700.0f) {

    motor.target = 0;

  }

  // Diagnostic: print phase currents at 5 Hz

  static unsigned long last_print = 0;

  if (millis() - last_print > 200) {

    last_print = millis();

    PhaseCurrent_s ic = currentSense.getPhaseCurrents();

    Serial.print("target=");      Serial.print(motor.target, 2);

    Serial.print("  vel=");       Serial.print(motor.shaft_velocity, 1);

    Serial.print("  i_a=");       Serial.print(ic.a, 3);

    Serial.print("  i_b=");       Serial.print(ic.b, 3);

    Serial.print("  i_c=");       Serial.print(ic.c, 3);

    Serial.print("  sum=");       Serial.println(ic.a + ic.b + ic.c, 3);

  }

}

Happy to share the simulation work, parameter ID, etc. if useful. Right now I’m stuck, and any pointers from people who have working MB1419C foc_current setups would be incredibly helpful.

Thanks againnnnn~~

Hmm, I still don’t see anything. Try printing the current a,b,c and motor.Ua,Ub,Uc voltages at the same time, to make sure it’s actually trying. And try printing while turning slowly in open loop mode to see what the current to voltage ratio should be (of course set motor.voltage_limit much lower before switching to open loop, since it applies full voltage at all times).

Here’s my code, for comparison. I always use sprintf for realtime output since Serial.print will block execution on STM32 if you call it twice within 20ms or so. However it does not support %f floating point numbers, so you have to multiply by 1000 and cast to int so the printed values are in millivolts and milliamps.

// RCTimer 5010 620kv lathe mini-spindle

#include <SimpleFOC.h>
#include <SimpleFOCDrivers.h>
#include <encoders/MXLEMMING_observer/MXLEMMINGObserverSensor.h>

typedef int8_t s8;
typedef uint8_t u8;
typedef int16_t s16;
typedef uint16_t u16;
typedef int32_t s32;
typedef uint32_t u32;
typedef int64_t s64;
typedef uint64_t u64;

#define SERVO_PULSE_PIN PA15

// BLDC motor & driver instance
BLDCMotor motor = BLDCMotor(7, 0.07f, 620, 0.000045f);
BLDCDriver6PWM driver = BLDCDriver6PWM(A_PHASE_UH, A_PHASE_UL, A_PHASE_VH, A_PHASE_VL, A_PHASE_WH, A_PHASE_WL);
LowsideCurrentSense currentSense = LowsideCurrentSense(0.003f, -64.0f/7.0f, A_OP1_OUT, A_OP2_OUT, A_OP3_OUT);
MXLEMMINGObserverSensor lemming = MXLEMMINGObserverSensor(motor);

extern volatile u16 adcBuffer1[];
float GetTemperature() { return adcBuffer1[3] * (345.2f / 4096.0f) - 56.2f; }
float GetBusVoltage() { return adcBuffer1[4] * ((169.0f+18.0f) / 18.0f * 3.3f / 4096.0f); }

float target = 0;
char printVariable = 0;


u16 servoPulse = 0xffff; // Servo tester 982-2039
LowPassFilter servoLPF(0.1f);

void ServoPulseUpdate() {
  static u32 startTime = 0, lastPulseTime = 0;
  static int pinState = 0;
  u32 curTime = micros();
  int newState = digitalRead(SERVO_PULSE_PIN);
  if (newState != pinState) {
    if ((pinState = newState)) // Update static variable and check if transitioned from low to high
      startTime = curTime; // Transitioned from low to high: Start counting pulse time
    else if (curTime > startTime + 850 && curTime < startTime + 2150) // Transitioned from high to low: Check if valid signal
      servoPulse = (u16)(curTime - startTime), lastPulseTime = curTime;
    else
      servoPulse = 0xffff; // Pulse outside valid range
  }
  // Disable motor if no signal for over 100ms
  if (curTime - lastPulseTime > 100000)
    servoPulse = 0xffff;
}

void setup() {
  // use monitoring with serial 
  Serial.setTx(PB3);
  Serial.setRx(PB4);
  Serial.begin(115200);
  Serial.println(F_CPU);

  pinMode(SERVO_PULSE_PIN, INPUT);

  // For safety, make sure speed knob is turned to zero at startup.
  while(servoPulse == 0xffff) { delayMicroseconds(50); ServoPulseUpdate(); }
  while((servoPulse - 1000) * (6.5f / 1000.0f) > 10) { delayMicroseconds(50); ServoPulseUpdate(); }

  // link the motor to the sensor
  motor.linkSensor(&lemming);

  // driver config
  // power supply voltage [V]
  driver.voltage_power_supply = 12; // Will be updated to measured voltage after current sense starts the ADC
  driver.pwm_frequency = 25000;
  driver.init();
  // link the motor and the driver
  motor.linkDriver(&driver);
  // link current sense and the driver
  currentSense.linkDriver(&driver);

  // current sensing
  currentSense.init();
  if (GetBusVoltage() > 10 && GetBusVoltage() < 30) // Sanity check, e.g. powered by STLink with no battery connected
    driver.voltage_power_supply = GetBusVoltage();
  // no need for aligning
  currentSense.skip_align = true;
  motor.linkCurrentSense(&currentSense);

  // aligning voltage [V]
  motor.voltage_sensor_align = .6;
  // index search velocity [rad/s]
  motor.velocity_index_search = 3;

  // set motion control loop to be used
  motor.torque_controller = TorqueControlType::foc_current;
  motor.controller = MotionControlType::torque;
  motor.foc_modulation = FOCModulationType::SpaceVectorPWM;

  // contoller configuration 
  // default parameters in defaults.h

  // velocity PI controller parameters
  motor.PID_velocity.P = 0.1;
  motor.PID_velocity.I = 10.0f;
  motor.PID_velocity.D = 0.0f;
  // default voltage_power_supply
  motor.voltage_limit = 0;
  motor.current_limit = 5;
  // jerk control using voltage voltage ramp
  // default value is 300 volts per sec  ~ 0.3V per millisecond
  motor.PID_velocity.output_ramp = 20;
  // velocity low pass filtering time constant
  motor.LPF_velocity.Tf = 0.01f;

  // angle P controller
  motor.P_angle.P = 20;
  //  maximal velocity of the position control
  motor.velocity_limit = 5000 / 60 * _2PI;

  // initialize motor
  motor.init();
  // align encoder and start FOC
  motor.zero_electric_angle = 0; motor.sensor_direction = Direction::CW; // Lemming
  motor.initFOC();
}

void loop() {
  u32 loopTime = _micros();

  ServoPulseUpdate();

  static int voltageTarget = 0;
  if (servoPulse == 0xffff)
    voltageTarget = 0;
  else {
    target = -motor.current_limit; // Apply full torque, with max RPM controlled by voltage limit
    int newTarget = servoLPF((servoPulse - 1000) * (650.0f / 1000.0f));
    static const int speed[7] = { 10, 100, 200, 300, 400, 500, 600 };
    int v;
    for (v = sizeof(speed)/sizeof(speed[0])-1; v >= 0; v--)
      if (newTarget >= speed[v])
        break;
    if (v < voltageTarget - 1) v += 1, voltageTarget = v < 0 ? 0 : v;
    else if (v > voltageTarget) voltageTarget = v;
  }

  // limit the acceleration by ramping the output
  float dt = 0.000050f, dv = voltageTarget - motor.voltage_limit, ramp = 20*dt; // Ramp at 20V/s
  if(dv > ramp) motor.voltage_limit += ramp;
  else if(dv < -ramp) motor.voltage_limit -= ramp;
  else motor.voltage_limit = voltageTarget;

  if (motor.voltage_limit == 0 && motor.enabled)
    motor.disable(); // Disable passive braking effect
  else if (motor.voltage_limit != 0 && !motor.enabled)
    motor.enable();

  motor.PID_current_q.limit = motor.PID_current_d.limit = motor.voltage_limit;
  target = motor.voltage_limit == 0 ? 0 : -motor.current_limit;

  motor.loopFOC();
  motor.move(target);

  loopTime = _micros() - loopTime;

  static uint32_t lastPrintTime = 0;
  u32 t = millis();
  if (printVariable && t >= lastPrintTime + 50)
  {
    lastPrintTime = t;
    PhaseCurrent_s c = currentSense.getPhaseCurrents();
    DQCurrent_s f = currentSense.getFOCCurrents(motor.electrical_angle);
    float dc = currentSense.getDCCurrent();
    char string[256];
    switch(printVariable)
    {
    case 'b': sprintf(string, "%i\n", (int)(GetBusVoltage()*1000)); break;
    case 'h': sprintf(string, "%i\n", (int)(GetTemperature()*1000)); break;
    case 'v': sprintf(string, "%i\n", (int)(motor.shaft_velocity*1000)); break;
    case 'd': sprintf(string, "%+5i\n", (int)(dc*1000)); break;
    case 'l': sprintf(string, "%i\n", loopTime); break;
    case 'u': sprintf(string, "%+5i,%+5i,%+5i\n", (int)(motor.Ua*1000), (int)(motor.Ub*1000), (int)(motor.Uc*1000)); break;
    case 'c': sprintf(string, "%+5i,%+5i,%+5i\n", (int)(c.a*1000), (int)(c.b*1000), (int)(c.c*1000)); break;
    case 'f': sprintf(string, "%+5i,%+5i\n", (int)(f.d*1000), (int)(f.q*1000)); break;
    case 'p': sprintf(string, "%i\n", (int)servoPulse); break;
    case 't': sprintf(string, "%i\n", (int)target); break;
    default: string[0] = 0;
    }
    if(string[0]) Serial.print(string);
  }

  SerialComm();
}

void SerialComm()
{
  switch(Serial.read())
  {
  case '!': delay(2); printVariable = Serial.available() ? Serial.read() : 0; break;
  case 's': Serial.print("shaft_velocity "); Serial.println(motor.shaft_velocity); break;
  case 'a': Serial.print("shaft_angle ");  Serial.println(motor.shaft_angle); break;
  case 'h': Serial.print("Temperature "); Serial.println(GetTemperature()); break;
  case 'b': Serial.print("Bus voltage "); Serial.println(GetBusVoltage()); break;
  case 'N': motor.controller = (MotionControlType)(int)Serial.parseInt(); Serial.print("Set ");
  case 'n': Serial.print("controller "); Serial.println(motor.controller); break;
  case 'M': motor.foc_modulation = (FOCModulationType)Serial.parseInt(); Serial.print("Set ");
  case 'm': Serial.print("foc_modulation "); Serial.println(motor.foc_modulation); break;
  case 'Q': motor.torque_controller = (TorqueControlType)Serial.parseInt(); Serial.print("Set ");
  case 'q': Serial.print("torque_controller "); Serial.println(motor.torque_controller); break;
  case 'K': motor.KV_rating = Serial.parseFloat();
    lemming.flux_linkage = 60 / ( _SQRT3 * _PI * motor.KV_rating * motor.pole_pairs * 2);
    Serial.print("Set ");
  case 'k': Serial.print("KV_rating "); Serial.println(motor.KV_rating); break;
  case 'R': motor.phase_resistance = Serial.parseFloat(); Serial.print("Set ");
  case 'r': Serial.print("phase_resistance "); Serial.println(motor.phase_resistance); break;
  case 'L': motor.phase_inductance = Serial.parseFloat(); Serial.print("Set ");
  case 'l': Serial.print("phase_inductance "); Serial.println(motor.phase_inductance); break;
  case 'Z': motor.zero_electric_angle = Serial.parseFloat(); Serial.print("Set ");
  case 'z': Serial.print("zero_electric_angle "); Serial.println(motor.zero_electric_angle); break;
  case 'T': target = Serial.parseFloat(); Serial.print("Set target "); Serial.println(target); break;
  case 't': Serial.print("target "); Serial.println(target); break;

  case 'U': driver.voltage_power_supply = Serial.parseFloat(); Serial.print("Set ");
  case 'u': Serial.print("voltage_power_supply "); Serial.println(driver.voltage_power_supply); break;
  case 'V': motor.voltage_limit = motor.PID_current_q.limit = motor.PID_current_d.limit = Serial.parseFloat(); Serial.print("Set ");
  case 'v': Serial.print("voltage_limit "); Serial.println(motor.voltage_limit); break;
  case 'C': motor.current_limit = motor.PID_velocity.limit = Serial.parseFloat(); Serial.print("Set ");
  case 'c': Serial.print("current_limit "); Serial.println(motor.current_limit); break;

  case 'O': motor.PID_velocity.output_ramp = Serial.parseFloat(); Serial.print("Set ");
  case 'o': Serial.print("PID_velocity.output_ramp "); Serial.println(motor.PID_velocity.output_ramp); break;
  case 'F': motor.LPF_velocity.Tf = Serial.parseFloat(); Serial.print("Set ");
  case 'f': Serial.print("LPF_velocity.Tf "); Serial.println(motor.LPF_velocity.Tf); break;
  case 'E': motor.LPF_angle.Tf = Serial.parseFloat(); Serial.print("Set ");
  case 'e': Serial.print("LPF_angle.Tf "); Serial.println(motor.LPF_angle.Tf); break;
  case 'P': motor.PID_velocity.P = Serial.parseFloat(); Serial.print("Set ");
  case 'p': Serial.print("PID_velocity.P "); Serial.println(motor.PID_velocity.P); break;
  case 'I': motor.PID_velocity.I = Serial.parseFloat(); Serial.print("Set ");
  case 'i': Serial.print("PID_velocity.I "); Serial.println(motor.PID_velocity.I); break;
  case 'D': motor.PID_velocity.D = Serial.parseFloat(); Serial.print("Set ");
  case 'd': Serial.print("PID_velocity.D "); Serial.println(motor.PID_velocity.D); break;

  case 'W': motor.P_angle.P = Serial.parseFloat(); Serial.print("Set ");
  case 'w': Serial.print("P_angle.P "); Serial.println(motor.P_angle.P); break;
  }
}