In order to make the steering wheel easier to drive when autosteer is off but the motor still engaged on the steering wheel, I ordered a Brushless motor.
It has no gear reduction so very low torque when not supplied with power.
I ordered also a ESC (motor controller) for brushless motor to drive it. It will replace the Cytron.
My concern is about the PWM to be sent to the ESC.
The ESC should normally be driven by a remote control reveiver with a “servo-type” PWM, without “DIR” signal.
It means that with
PWM = 0, motor drives full speed left ;
PWM = 50, motor is stopped ;
PWM 100 motor drives full speed right.
Has anyone already modified the Autosteer arduino sketch to send such values out ?
If not, I plan to add an aditionnal Arduino connected to the PCB V2 pwm and dir pin, to read the values comming out from the PCB and “translate” it to my ESC.
It has the advantage to let the Agopengps sketch like it is.
void motorDrive(void){
// Used with Cytron MD30C Driver
// Steering Motor
// Dir + PWM Signal
if (aogSettings.CytronDriver){
pwmDisplay = pwmDrive;
int pwmServo = pwmDrive;
//fast set the direction accordingly (this is pin DIR1_RL_ENABLE, port D, 4)
if (pwmDrive >= 0){
bitSet(PORTD, 4); //set the correct direction
digitalWrite(PWM2_RPWM, 0);
} else {
bitClear(PORTD, 4);
digitalWrite(PWM2_RPWM, 1);
pwmDrive = -1 * pwmDrive;
}
//write out the 0 to 255 value
//pwmDrive = 255 - pwmDrive;
//analogWrite(PWM1_LPWM, pwmDrive); // don't need this but still select Cytron in AoG
if (pwmServo > 0){
pwmServo += 1; // +-1 before multiplying
pwmServo = int(float(pwmServo) * 1.6); // my motor needs a different gain for this direction, it's not symetrical
}
else if (pwmServo < 0) pwmServo -= 1;
pwmServo *= 2; // *2 gets the pwmDrive into range for Servo microseconds output
if (pwmServo > 0) pwmServo -= 1; // revert previous +-1
else if (pwmServo < 0) pwmServo += 1;
pwmServo += 1410; // offset for 1500 uS servo center output, adjust for your drive
myServo.writeMicroseconds(pwmServo);
} else {
// Used with IBT 2 Driver for Steering Motor
// Dir1 connected to BOTH enables
// PWM Left + PWM Right Signal
pwmDisplay = pwmDrive;
if (pwmDrive > 0) {
analogWrite(PWM2_RPWM, 0); //Turn off before other one on
analogWrite(PWM1_LPWM, pwmDrive);
} else {
pwmDrive = -1 * pwmDrive;
analogWrite(PWM1_LPWM, 0); //Turn off before other one on
analogWrite(PWM2_RPWM, pwmDrive);
}
}
}
You have to select Cytron in AoG but it will output a Servo signal on PWM1_LPWM (IO 3).
I had to play around to find the true center/zero of my ESC, then I entered that in for the center offset (see comments in the above code)
I too am looking at BLDC motors for steering control as they can result in very compact mechanics. It may even be possible to use a skateboard wheel with inbuilt motor if the gear ratio/ torque works. Looking at the VESC code and tool info, you can setup to drive via servo, uart, ADC or CAN. Other choices are sensored or sensorless, and FOC control or not. Sensored and FOC should in theory give better starting and lower cogging, but are they necessary?
I believe that a motor with a high pole number and low KV is needed more than anything else, in order to have a lot of starting torque and little speed inertia
I tried a bdlc this weekend, a 6374-170Kv from amazon / aliexpress, I was disappointed, and I came to the same conclusion … You need a large number of poles.
Also was the motor properly set up with the Vesc tool for inductance, motor type , voltage etc? One problem could be running on low tractor voltage 12-14volts, some BLDC motors are designed for much higher voltages to give more torque. But yes, the more poles the better and low KV.
I tried with FOC, current control, hall sensors, BUT, at very low rpm the vesc still works in openloop, and in my opinion this can be a problem, maybe try with a high reduction ratio