混合 2 轴模拟输入以控制差动电机驱动的算法

电器工程 模拟 直流电机 脉宽调制 遥控 混合器
2022-01-31 09:43:15

我正在寻找有关如何正确混合 2 个模拟操纵杆信号(X 和 Y 轴)以使用 uC(在我的情况下为 ATMega328p,但同样适用于任何带有 ADC 输入和 PWM 输出的 uC):

我有一个模拟棒,它提供 2 个模拟值:

(方向)X: 0 到 1023
(油门)Y: 0 到 1023

在此处输入图像描述

静止位置是(方向和油门空档) 512,512
油门向前/向左方向是 0,0
完全向前 - 完全向右是 1023,0
等。

电机由 2 个 H 桥驱动器控制,每个驱动器有 2 个 PWM 引脚(正向、反向),如下所示:
左电机:-255 至 255
右电机:-255 至 255
(正值启用正向 PWM 引脚,负值启用反向PWM 引脚,0 禁用两者)

目标是混合操纵杆模拟信号以实现以下响应:

a) 油门前进,空档方向 = 车辆前进
b) 油门前进,左方向 = 车辆前进并左转
c) 油门空档,左方向 = 车辆左转

...对于其他组合也是如此。当然,输出应该是“模拟的”,也就是说,它应该允许从例如选项 a) 到 b) 到 c) 的逐渐过渡。

这个概念是:

http://www.lynxmotion.com/images/html/build123.htm

3个回答

这是一个不需要复杂的 if/else 链的解决方案,在完全向前移动或原地旋转时不会降低功率,并且允许平滑的曲线和从移动到旋转的过渡。

这个想法很简单。假设 (x,y) 操纵杆值是正方形平面上的笛卡尔坐标。现在想象一个较小的方形平面在其中旋转 45º。

示例飞机

操纵杆坐标为您提供较大正方形中的一个点,叠加在较小正方形中的同一点为您提供电机值。您只需要将坐标从一个正方形转换到另一个正方形,将新的 (x,y) 值限制在较小正方形的边上。

有很多方法可以进行转换。我最喜欢的方法是:

  1. 将初始 (x,y) 坐标转换为极坐标。
  2. 将它们旋转 45 度。
  3. 将极坐标转换回笛卡尔坐标。
  4. 将新坐标重新缩放为 -1.0/+1.0。
  5. 将新值限制为 -1.0/+1.0。

这假设初始 (x,y) 坐标在 -1.0/+1.0 范围内。内部正方形的边总是等于l * sqrt(2)/2,所以第 4 步只是将值乘以sqrt(2)

这是一个示例 Python 实现。

import math

def steering(x, y):
    # convert to polar
    r = math.hypot(x, y)
    t = math.atan2(y, x)

    # rotate by 45 degrees
    t += math.pi / 4

    # back to cartesian
    left = r * math.cos(t)
    right = r * math.sin(t)

    # rescale the new coords
    left = left * math.sqrt(2)
    right = right * math.sqrt(2)

    # clamp to -1/+1
    left = max(-1, min(left, 1))
    right = max(-1, min(right, 1))

    return left, right

这种方法的最初想法——使用更复杂的转换方法——来自这篇文章

“正确”的混合是有争议的:-)。

一个问题是,您必须决定轨道在来自单个底池的纯信号下移动的速度,以及当包含来自另一个底池的信号时该怎么做。例如,如果您将 FB(Forward-Backward 电位器完全向前推,并且如果两个电机都在前面全速运行,那么您如何处理添加了少量的 LR(Left-Right)电位器。获得旋转,你必须让一个轨道比另一个更快。所以,如果你已经在两个电机上以最大前进速度运行,你必须降低一个或另一个轨道速度才能转弯。但是,如果你一直站着不动,你会加速一个或其他轨道以达到相同的结果。

所以,说了这么多,这是一个简单的即兴启动解决方案,这似乎是一个好的开始。

如果罐在机械上是独立的,那么两者可以同时处于 100%。
如果两者都在操纵杆型布置上,如果 Yaxis = 100% 和 Xaxis = 0%,则添加一些 B 通常会减少 A。可以在上述不正确的情况下构造操纵杆,但这些都是不寻常的。
假设操纵杆属于当 X = 100% 时增加 Y% 会减小 X 的类型。可以进行其他假设。

FB = 前后锅。中心零,+Ve 用于锅的向前运动

LR = 左右锅。中心零。+Ve 右边的锅。

K 最初是比例因子 1。
如果任何结果超过 100%,则调整 K,使结果 = 100%,并对其他电机也使用相同的 K 值。

  • 例如,如果左电机结果 = 125,右电机结果 = 80。
    由于 125 x 0.8 = 100,设置 K = 0.8。然后。
    左 = 125 x 0.8 = 100%。右 = 80 x 0.8 = 64%。

然后:

  • 左电机 = K x (Front_Back + Left_Right)

  • 右电机 = K x (Front_Back - Left_Right)

健全性检查:

  • LR = 0(居中),FB = 全正向 -> 两个电机全正向运行。

  • LR = 完全向左,FB = 0 ->
    左侧电机向后完全运行,
    右侧电机向前完全运行。
    车辆逆时针旋转。

  • FB 为 100%,Lr = 0%。向右添加 10% 的 LR。
    L = FB+LR = 100%- + 10% R = FB-LR = 100%- - 10%

如果最大轴 < 100%,则缩放直到 = 100%。
然后以相同的量缩放其他轴。

以下是 Russel McMahon 回答中描述的混合算法实现示例:

http://www.youtube.com/watch?v=sGpgWDIVsoE

//Atmega328p based Arduino code (should work withouth modifications with Atmega168/88), tested on RBBB Arduino clone by Modern Device:
const byte joysticYA = A0; //Analog Jostick Y axis
const byte joysticXA = A1; //Analog Jostick X axis

const byte controllerFA = 10; //PWM FORWARD PIN for OSMC Controller A (left motor)
const byte controllerRA = 9;  //PWM REVERSE PIN for OSMC Controller A (left motor)
const byte controllerFB = 6;  //PWM FORWARD PIN for OSMC Controller B (right motor)
const byte controllerRB = 5;  //PWM REVERSE PIN for OSMC Controller B (right motor)
const byte disablePin = 2; //OSMC disable, pull LOW to enable motor controller

int analogTmp = 0; //temporary variable to store 
int throttle, direction = 0; //throttle (Y axis) and direction (X axis) 

int leftMotor,leftMotorScaled = 0; //left Motor helper variables
float leftMotorScale = 0;

int rightMotor,rightMotorScaled = 0; //right Motor helper variables
float rightMotorScale = 0;

float maxMotorScale = 0; //holds the mixed output scaling factor

int deadZone = 10; //jostick dead zone 

void setup()  { 

  //initialization of pins  
  Serial.begin(19200);
  pinMode(controllerFA, OUTPUT);
  pinMode(controllerRA, OUTPUT);
  pinMode(controllerFB, OUTPUT);
  pinMode(controllerRB, OUTPUT);  

  pinMode(disablePin, OUTPUT);
  digitalWrite(disablePin, LOW);
} 

void loop()  { 
  //aquire the analog input for Y  and rescale the 0..1023 range to -255..255 range
  analogTmp = analogRead(joysticYA);
  throttle = (512-analogTmp)/2;

  delayMicroseconds(100);
  //...and  the same for X axis
  analogTmp = analogRead(joysticXA);
  direction = -(512-analogTmp)/2;

  //mix throttle and direction
  leftMotor = throttle+direction;
  rightMotor = throttle-direction;

  //print the initial mix results
  Serial.print("LIN:"); Serial.print( leftMotor, DEC);
  Serial.print(", RIN:"); Serial.print( rightMotor, DEC);

  //calculate the scale of the results in comparision base 8 bit PWM resolution
  leftMotorScale =  leftMotor/255.0;
  leftMotorScale = abs(leftMotorScale);
  rightMotorScale =  rightMotor/255.0;
  rightMotorScale = abs(rightMotorScale);

  Serial.print("| LSCALE:"); Serial.print( leftMotorScale,2);
  Serial.print(", RSCALE:"); Serial.print( rightMotorScale,2);

  //choose the max scale value if it is above 1
  maxMotorScale = max(leftMotorScale,rightMotorScale);
  maxMotorScale = max(1,maxMotorScale);

  //and apply it to the mixed values
  leftMotorScaled = constrain(leftMotor/maxMotorScale,-255,255);
  rightMotorScaled = constrain(rightMotor/maxMotorScale,-255,255);

  Serial.print("| LOUT:"); Serial.print( leftMotorScaled);
  Serial.print(", ROUT:"); Serial.print( rightMotorScaled);

  Serial.print(" |");

  //apply the results to appropriate uC PWM outputs for the LEFT motor:
  if(abs(leftMotorScaled)>deadZone)
  {

    if (leftMotorScaled > 0)
    {
      Serial.print("F");
      Serial.print(abs(leftMotorScaled),DEC);

      analogWrite(controllerRA,0);
      analogWrite(controllerFA,abs(leftMotorScaled));            
    }
    else 
    {
      Serial.print("R");
      Serial.print(abs(leftMotorScaled),DEC);

      analogWrite(controllerFA,0);
      analogWrite(controllerRA,abs(leftMotorScaled));  
    }
  }  
  else 
  {
  Serial.print("IDLE");
  analogWrite(controllerFA,0);
  analogWrite(controllerRA,0);
  } 

  //apply the results to appropriate uC PWM outputs for the RIGHT motor:  
  if(abs(rightMotorScaled)>deadZone)
  {

    if (rightMotorScaled > 0)
    {
      Serial.print("F");
      Serial.print(abs(rightMotorScaled),DEC);

      analogWrite(controllerRB,0);
      analogWrite(controllerFB,abs(rightMotorScaled));            
    }
    else 
    {
      Serial.print("R");
      Serial.print(abs(rightMotorScaled),DEC);

      analogWrite(controllerFB,0);
      analogWrite(controllerRB,abs(rightMotorScaled));  
    }
  }  
  else 
  {
  Serial.print("IDLE");
  analogWrite(controllerFB,0);
  analogWrite(controllerRB,0);
  } 

  Serial.println("");

  //To do: throttle change limiting, to avoid radical changes of direction for large DC motors

  delay(10);

}