移動機器人技術(9)-- 全向移動機器人Modeling and Control


之前寫的文章分析了全向小車運動原理和基本構型,今天嘗試把它部署到 Ros 上。


基本原理

參考系的定義需要根據 Ros by Example chapter 7 做一些修改:

  • 定義三輪車的三個輪子分別是 A、B、C, 速度分別是a、b、c;
  • 定義半徑 Radius 是中點到輪子的距離;
  • 定義 a,b 爲前輪,c 爲後輪。

控制程序

Ros 中的的速度消息是 Twist 指定的

$ rosmsg show geometry_msgs/Twist
geometry_msgs/Vector3 linear
  float64 x
  float64 y
  float64 z
geometry_msgs/Vector3 angular
  float64 x
  float64 y
  float64 z

linear 中的 x 代表前進的速度,單位是 m/s 。angular 中的 z 表示角速度,單位 rad/s。

python 實現,由於小車控制器和電機自帶PID控制,只需寫一個發佈速度的節點:

#!/usr/bin/env python
# -*- coding: utf-8 -*-

import rospy
from geometry_msgs.msg import Twist
from math import sqrt
import RPi.GPIO as GPIO
import time
import sys

Radius = 10 #圓盤半徑,需要根據情況修改

PWMA = 18
AIN1 = 22
AIN2 = 27

PWMB = 23
BIN1 = 25
BIN2 = 24

PWMC = 16
CIN1 = 20
CIN2 = 21

GPIO.setwarnings(False) 
GPIO.setmode(GPIO.BCM)

GPIO.setup(AIN2,GPIO.OUT)
GPIO.setup(AIN1,GPIO.OUT)
GPIO.setup(PWMA,GPIO.OUT)

GPIO.setup(BIN1,GPIO.OUT)
GPIO.setup(BIN2,GPIO.OUT)
GPIO.setup(PWMB,GPIO.OUT)

GPIO.setup(CIN1,GPIO.OUT)
GPIO.setup(CIN2,GPIO.OUT)
GPIO.setup(PWMC,GPIO.OUT)

A_Motor= GPIO.PWM(PWMA,100)
A_Motor.start(0)

B_Motor = GPIO.PWM(PWMB,100)
B_Motor.start(0)

C_Motor = GPIO.PWM(PWMC,100)
C_Motor.start(0)

def compute(Vx,Vy,omega):
    a = -sqrt(3)/3 * Vx + 1/3 * Vy + omega * Radius
    b =  sqrt(3)/3 * Vx + 1/3 * Vy + omega * Radius
    c =                 - 2/3 * Vy + omega * Radius
       
    return a,b,c 

def move(va,vb,vc,t_time = 4):
    A_Motor.ChangeDutyCycle(abs(va))
    GPIO.output(AIN1,bool(va<0))
    GPIO.output(AIN2,bool(va>0))

    B_Motor.ChangeDutyCycle(abs(vb))
    GPIO.output(BIN1,bool(vb<0))
    GPIO.output(BIN2,bool(vb>0))
    
    C_Motor.ChangeDutyCycle(abs(vc))
    GPIO.output(CIN1,bool(vc<0))
    GPIO.output(CIN2,bool(vc>0))

    time.sleep(t_time)

def callback(msg):
    rospy.loginfo("Received a /cmd_vel message!")
    rospy.loginfo("Linear Velocity: [%f, %f, %f]"%(msg.linear.x, msg.linear.y, msg.linear.z))
    rospy.loginfo("Angular Velocity: [%f, %f, %f]"%(msg.angular.x, msg.angular.y, msg.angular.z))

    # 速度獲取
    omega = msg.angular.z #角速度
    Vx = msg.linear.x
    Vy = msg.linear.y

    va,vb,vc = compute(Vx, Vy, omega)
    
    rospy.loginfo("va: %f, vb: %f, vc: %f]"%(va, vb, vc))

    move(va,vb,vc)

def listener():
    rospy.init_node('vel_listener')
    rospy.Subscriber('/cmd_vel', Twist, callback)
    rospy.spin()

if __name__ == "__main__":
    try:
        listener()
    except KeyboardInterrupt:
        GPIO.cleanup()

 

 

 

發表評論
所有評論
還沒有人評論,想成為第一個評論的人麼? 請在上方評論欄輸入並且點擊發布.
相關文章