Patrulla de línea

Vídeo tutorial 20 - Patrulla de línea: https://singtown.com/learn/50037/

Este ejemplo muestra la regresión lineal del ROI usando el método get_regression() en OpenMV Cam. Con este método, es fácil hacer que el robot siga todas las líneas que apuntan en la misma dirección general.

Esta rutina se puede utilizar para patrullar líneas de robots y el efecto es muy bueno.

El coche persiguiendo la pelota

Vídeo tutorial 9 - Coche persiguiendo la pelota: https://singtown.com/learn/49239/

preparar materiales

  • Placa OpenMV x1:\

  • Suelo de coche impreso en 3D:

  • Batería de litio de 3,7 V x1:

  • Placa controladora de motor TB6612 x1:

  • Rueda de ojo de buey x2:

  • Motor N20 DC x2 (incluida base fija, incluidos neumáticos):

  • Tuerca de tornillo M3*20 x2:

  • M2*4 tornillos autorroscantes x2

Conecte el circuito y pruebe el motor

Escribe el módulo del coche

En primer lugar, debemos responder: ¿por qué necesitamos escribir módulos? No es difícil accionar el motor directamente. – Debido a que el código es más reutilizable de esta manera, la lógica de control es independiente de la estructura del automóvil. Para diferentes coches, simplemente cambia el módulo del coche.

car.py

from pyb import Pin, Timer
inverse_left=False  #change it to True to inverse left wheel
inverse_right=False #change it to True to inverse right wheel

ain1 =  Pin('P0', Pin.OUT_PP)
ain2 =  Pin('P1', Pin.OUT_PP)
bin1 =  Pin('P2', Pin.OUT_PP)
bin2 =  Pin('P3', Pin.OUT_PP)
ain1.low()
ain2.low()
bin1.low()
bin2.low()

pwma = Pin('P7')
pwmb = Pin('P8')
tim = Timer(4, freq=1000)
ch1 = tim.channel(1, Timer.PWM, pin=pwma)
ch2 = tim.channel(2, Timer.PWM, pin=pwmb)
ch1.pulse_width_percent(0)
ch2.pulse_width_percent(0)

def run(left_speed, right_speed):
    if inverse_left==True:
        left_speed=(-left_speed)
    if inverse_right==True:
        right_speed=(-right_speed)

    if left_speed < 0:
        ain1.low()
        ain2.high()
    else:
        ain1.high()
        ain2.low()
    ch1.pulse_width_percent(int(abs(left_speed)))

    if right_speed < 0:
        bin1.low()
        bin2.high()
    else:
        bin1.high()
        bin2.low()
    ch2.pulse_width_percent(int(abs(right_speed)))

Guarde el archivo anterior como car.py Según Uso del módulo, guarde car.py en OpenMV.

Pruebe el código en el IDE:\ main.py

import car

while True:
    car.run(100,100)

Verifique si el automóvil se está moviendo hacia adelante. De lo contrario, cambie la inversa_izquierda y la inversa_derecha de la segunda y tercera líneas para invertir las ruedas izquierda o derecha para asegurarse de que el automóvil se esté moviendo hacia adelante.

Implementación del algoritmo PID

El algoritmo pid es un algoritmo ampliamente utilizado en el control y existen muchos principios en Internet.\ https://zh.wikipedia.org/wiki/Controlador PID\ http://baike.baidu.com/link?url=-obQq78Ur4bTeqA10bIniO6y0euQFcWL9WW18vq2hA3fyHN3rt32o79F2WPE7cK0Di9M6904rlHD9ttvVTySIK\ El código sigue siendo muy simple. Copié directamente el código fuente de un control de vuelo:\ https://github.com/wagnerc4/flight_controller/blob/master/pid.py\ Es una copia de ArduPilot.\ https://github.com/ArduPilot/ardupilot

pid.py

from pyb import millis
from math import pi, isnan

class PID:
    _kp = _ki = _kd = _integrator = _imax = 0
    _last_error = _last_derivative = _last_t = 0
    _RC = 1/(2 * pi * 20)
    def __init__(self, p=0, i=0, d=0, imax=0):
        self._kp = float(p)
        self._ki = float(i)
        self._kd = float(d)
        self._imax = abs(imax)
        self._last_derivative = float('nan')

    def get_pid(self, error, scaler):
        tnow = millis()
        dt = tnow - self._last_t
        output = 0
        if self._last_t == 0 or dt > 1000:
            dt = 0
            self.reset_I()
        self._last_t = tnow
        delta_time = float(dt) / float(1000)
        output += error * self._kp
        if abs(self._kd) > 0 and dt > 0:
            if isnan(self._last_derivative):
                derivative = 0
                self._last_derivative = 0
            else:
                derivative = (error - self._last_error) / delta_time
            derivative = self._last_derivative + \
                                     ((delta_time / (self._RC + delta_time)) * \
                                        (derivative - self._last_derivative))
            self._last_error = error
            self._last_derivative = derivative
            output += self._kd * derivative
        output *= scaler
        if abs(self._ki) > 0 and dt > 0:
            self._integrator += (error * self._ki) * scaler * delta_time
            if self._integrator < -self._imax: self._integrator = -self._imax
            elif self._integrator > self._imax: self._integrator = self._imax
            output += self._integrator
        return output
    def reset_I(self):
        self._integrator = 0
        self._last_derivative = float('nan')

Además, de acuerdo con Uso del módulo, guarde pid.py en OpenMV.

Ajuste los parámetros para lograr lo siguiente

Lo principal es ajustar los dos parámetros de PI, http://blog.csdn.net/zyboy2000/article/details/9418257

THRESHOLD = (5, 70, -23, 15, -57, 0) # Grayscale threshold for dark things...
import sensor, image, time
from pyb import LED
import car
from pid import PID
rho_pid = PID(p=0.4, i=0)
theta_pid = PID(p=0.001, i=0)

LED(1).on()
LED(2).on()
LED(3).on()

sensor.reset()
sensor.set_vflip(True)
sensor.set_hmirror(True)
sensor.set_pixformat(sensor.RGB565)
sensor.set_framesize(sensor.QQQVGA) # 80x60 (4,800 pixels) - O(N^2) max = 2,3040,000.
#sensor.set_windowing([0,20,80,40])
sensor.skip_frames(time = 2000)     # WARNING: If you use QQVGA it may take seconds
clock = time.clock()                # to process a frame sometimes.

while(True):
    clock.tick()
    img = sensor.snapshot().binary([THRESHOLD])
    line = img.get_regression([(100,100)], robust = True)
    if (line):
        rho_err = abs(line.rho())-img.width()/2
        if line.theta()>90:
            theta_err = line.theta()-180
        else:
            theta_err = line.theta()
        img.draw_line(line.line(), color = 127)
        print(rho_err,line.magnitude(),rho_err)
        if line.magnitude()>8:
            #if -40<b_err<40 and -30<t_err<30:
            rho_output = rho_pid.get_pid(rho_err,1)
            theta_output = theta_pid.get_pid(theta_err,1)
            output = rho_output+theta_output
            car.run(50+output, 50-output)
        else:
            car.run(0,0)
    else:
        car.run(50,-50)
        pass
    #print(clock.fps())

Si desea hacer un automóvil que siga una línea, solo necesita usar el valor de retorno theta y rho del objeto de línea obtenido por este programa (theta representa el ángulo del segmento de línea devuelto, rho representa la distancia de desplazamiento) y usar theta y rho para controlar el ángulo del coche.

rho es más importante. Si no usas theta, puedes usar rho.

Representación de operaciones:

results matching ""

    No results matching ""