底盘四轮转向运动学解析(含代码)

目录

  • 写在前面的话
  • 四轮转向运动学解析
    • 四轮转向理论图解
    • robot_control.py 完整代码
      • 关键参数
      • 完整代码
    • 公式解析(根据代码)
      • 反相--模式1
        • 详细图解
      • 正相--模式2
      • 轴心--模式3

写在前面的话

网上找了很多资料,对于四轮转向运动学描述的很少,有部分涉及到的又将的很晦涩难懂。在论文研究大多是四轮转向动力学研究。很多文章中都会把四轮运动简化成二轮运行(自行车),但是都只讨论了前驱或者后驱的情况,把前驱或后驱中轴点的速度的速度当做整车的速度,跟我到的代码不对应。

本文是基于代码进行解析,一些前提条件本文忽略(什么刚体,侧滑之类的),把车子的中心作为运动中心,已知车速和角速度计算四轮的线速度和转向,希望大家可以看懂,主要难点是在反相运动的部分,需要着重注意。

四轮转向运动学解析

四轮转向理论图解

  • 三种模式
    • 同相运动(前后轮摆动方向相同)
    • 反相运动(前后轮摆动方法相反,如下图,前轮往右摆,那么后轮就往左摆)
    • 轴心旋转

在这里插入图片描述

下图中属于逆向运动学,也即是根据车子行驶的速度和角速度,求解车轮的速度和方向。图中在反相运动过程中示例是右转弯,前后轮应该都符合阿克曼角,属于四驱阿克曼(双阿克曼),图中不明显。

在这里插入图片描述

robot_control.py 完整代码

代码链接:humble/four_ws_ros2/src/four_ws_control/scripts/robot_control.py

创建了一个 joy 节点,监听 v e l m s g vel_{msg} velmsg, m o d e s e l e c t i o n mode_{selection} modeselection 两个参数
车子的速度设置: v e l m s g = [ l i n e a r x , l i n e a r y , l i n e a r z , a n g l e x , a n g l e y , a n g l e z ] 模式选择: m o d e s e l e c t i o n = [ 1 , 2 , 3 ] \begin{aligned} &\begin{gathered} &\text{车子的速度设置:}\\ &vel_{ msg} = [linear_x, linear_y, linear_z, angle_x, angle_y, angle_z]\\ \\ &\text{ 模式选择:}\\ &mode_{selection} = [1, 2, 3] \\ &\end{gathered} \end{aligned} 车子的速度设置:velmsg=[linearx,lineary,linearz,anglex,angley,anglez] 模式选择:modeselection=[1,2,3]

关键参数

  • 车轮间距(wheel_seperation): 同一车轴上左轮和右轮之间的距离。
  • 前后轮距(wheel_base):前后车轴之间的距离。
  • 车轮半径(wheel_radius):车轮的半径。
  • 车轮转向 y 偏移(wheel_steering_y_offset): 车轮转向装置偏离车轮中心线的横向偏移。 (可以理解转向器的转轴和车轮的垂直轴有偏移)
  • 转向轨迹 (steering_track): 计算公式为【车轮间距 - 2 * 车轮转向 y 偏移】。 这表示影响车辆操控性的有效轨道宽度。

在这里插入图片描述

完整代码

#!/usr/bin/python3
import math
import threading
import rclpy
import numpy as np
from rclpy.node import Node
from std_msgs.msg import Float64MultiArray
from geometry_msgs.msg import Twist
from sensor_msgs.msg import Joyvel_msg = Twist()  # robot velosity
mode_selection = 0 # 1:opposite phase, 2:in-phase, 3:pivot turn 4: noneclass Commander(Node):def __init__(self):super().__init__('commander')timer_period = 0.02self.wheel_seperation = 0.122self.wheel_base = 0.156self.wheel_radius = 0.026self.wheel_steering_y_offset = 0.03self.steering_track = self.wheel_seperation - 2*self.wheel_steering_y_offsetself.pos = np.array([0,0,0,0], float)self.vel = np.array([0,0,0,0], float) #left_front, right_front, left_rear, right_rearself.pub_pos = self.create_publisher(Float64MultiArray, '/forward_position_controller/commands', 10)self.pub_vel = self.create_publisher(Float64MultiArray, '/forward_velocity_controller/commands', 10)self.timer = self.create_timer(timer_period, self.timer_callback)def timer_callback(self):global vel_msg, mode_selection# opposite phaseif(mode_selection == 1):vel_steerring_offset = vel_msg.angular.z * self.wheel_steering_y_offsetsign = np.sign(vel_msg.linear.x)self.vel[0] = sign*math.hypot(vel_msg.linear.x - vel_msg.angular.z*self.steering_track/2, vel_msg.angular.z*self.wheel_base/2) - vel_steerring_offsetself.vel[1] = sign*math.hypot(vel_msg.linear.x + vel_msg.angular.z*self.steering_track/2, vel_msg.angular.z*self.wheel_base/2) + vel_steerring_offsetself.vel[2] = sign*math.hypot(vel_msg.linear.x - vel_msg.angular.z*self.steering_track/2, vel_msg.angular.z*self.wheel_base/2) - vel_steerring_offsetself.vel[3] = sign*math.hypot(vel_msg.linear.x + vel_msg.angular.z*self.steering_track/2, vel_msg.angular.z*self.wheel_base/2) + vel_steerring_offsetself.pos[0] = math.atan(vel_msg.angular.z*self.wheel_base/(2*vel_msg.linear.x + vel_msg.angular.z*self.steering_track+0.001))self.pos[1] = math.atan(vel_msg.angular.z*self.wheel_base/(2*vel_msg.linear.x - vel_msg.angular.z*self.steering_track+0.001))self.pos[2] = -self.pos[0]self.pos[3] = -self.pos[1]# in-phaseelif(mode_selection == 2):V = math.hypot(vel_msg.linear.x, vel_msg.linear.y)sign = np.sign(vel_msg.linear.x)if(vel_msg.linear.x != 0):ang = vel_msg.linear.y / vel_msg.linear.xelse:ang = 0self.pos[0] = math.atan(ang)self.pos[1] = math.atan(ang)self.pos[2] = self.pos[0]self.pos[3] = self.pos[1]self.vel[:] = sign*V# pivot turnelif(mode_selection == 3):self.pos[0] = -math.atan(self.wheel_base/self.steering_track)self.pos[1] = math.atan(self.wheel_base/self.steering_track)self.pos[2] = math.atan(self.wheel_base/self.steering_track)self.pos[3] = -math.atan(self.wheel_base/self.steering_track)self.vel[0] = -vel_msg.angular.zself.vel[1] = vel_msg.angular.zself.vel[2] = self.vel[0]self.vel[3] = self.vel[1]else:self.pos[:] = 0self.vel[:] = 0pos_array = Float64MultiArray(data=self.pos) vel_array = Float64MultiArray(data=self.vel) self.pub_pos.publish(pos_array)self.pub_vel.publish(vel_array)self.pos[:] = 0self.vel[:] = 0class Joy_subscriber(Node):def __init__(self):super().__init__('joy_subscriber')self.subscription = self.create_subscription(Joy,'joy',self.listener_callback,10)self.subscriptiondef listener_callback(self, data):global vel_msg, mode_selectionif(data.buttons[0] == 1):   # in-phase # A button of Xbox 360 controllermode_selection = 2elif(data.buttons[4] == 1): # opposite phase # LB button of Xbox 360 controllermode_selection = 1elif(data.buttons[5] == 1): # pivot turn # RB button of Xbox 360 controllermode_selection = 3else:mode_selection = 4vel_msg.linear.x = data.axes[1]*7.5vel_msg.linear.y = data.axes[0]*7.5vel_msg.angular.z = data.axes[3]*10if __name__ == '__main__':rclpy.init(args=None)commander = Commander()joy_subscriber = Joy_subscriber()executor = rclpy.executors.MultiThreadedExecutor()executor.add_node(commander)executor.add_node(joy_subscriber)executor_thread = threading.Thread(target=executor.spin, daemon=True)executor_thread.start()rate = commander.create_rate(2)try:while rclpy.ok():rate.sleep()except KeyboardInterrupt:passrclpy.shutdown()executor_thread.join()

公式解析(根据代码)

np.sign 是 NumPy 库中的一个函数,用于返回输入数组中每个元素的符号。它的主要作用是判断数值的正负,具体行为如下:

  1. 如果元素为正数,返回 1
  2. 如果元素为负数,返回 -1
  3. 如果元素为零,返回 0

反相–模式1

  • v x v_{x} vx 是车子前进的速度。
  • v z v_{z} vz 是车子旋转的角速度(也就是上图中的 w w w)。
  • t t t 是车轮间距。
  • b b b 是前后轮距。
  • y o f f s e t y_{offset} yoffset 是车轮和转向器的偏移。

v o f f s e t = v z ⋅ y o f f s e t 每个车轮的线速度(除以车轮半径就是角速度):  v l f = ( v x − v z ⋅ t 2 ) 2 + ( v z ⋅ b 2 ) 2 − v o f f s e t v r f = ( v x + v z ⋅ t 2 ) 2 + ( v z ⋅ b 2 ) 2 + v o f f s e t v l r = v l f v r r = v r f 每个车轮的转向:  p o s l f = tan ⁡ − 1 ( v z ⋅ b 2 ⋅ v x + v z ⋅ t + 0.001 ) pos ⁡ r f = tan ⁡ − 1 ( v z ⋅ b 2 ⋅ v x − v z ⋅ t + 0.001 ) 上式是介绍前轮的转向,后轮只要取负数即。 \begin{aligned}\\ &v_{offset} = v_z \cdot y_{offset} \\ \\ \\ &\text {每个车轮的线速度(除以车轮半径就是角速度): }\\ &\begin{gathered} v_{l f}= \sqrt{\left(v_x-\frac{v_z \cdot t}{2}\right)^2+\left(\frac{v_z \cdot b}{2}\right)^2}-v_{offset} \\ v_{r f}=\sqrt{\left(v_x+\frac{v_z \cdot t}{2}\right)^2+\left(\frac{v_z \cdot b}{2}\right)^2}+v_{offset} \\ v_{l r}=v_{l f} \\ v_{r r}=v_{r f} \end{gathered}\\ \\ &\text {每个车轮的转向: }\\ &\begin{gathered} & p o s_{l f}=\tan ^{-1}\left(\frac{v_z \cdot b}{2 \cdot v_x+v_z \cdot t + 0.001}\right) \\ & \operatorname{pos}_{r f}=\tan ^{-1}\left(\frac{v_z \cdot b}{2 \cdot v_x-v_z \cdot t +0.001}\right) \end{gathered}\\ &\text {上式是介绍前轮的转向,后轮只要取负数即。}\\ \end{aligned} voffset=vzyoffset每个车轮的线速度(除以车轮半径就是角速度)vlf=(vx2vzt)2+(2vzb)2 voffsetvrf=(vx+2vzt)2+(2vzb)2 +voffsetvlr=vlfvrr=vrf每个车轮的转向poslf=tan1(2vx+vzt+0.001vzb)posrf=tan1(2vxvzt+0.001vzb)上式是介绍前轮的转向,后轮只要取负数即。

详细图解

根据上述的控制代码,得到车子的中心瞬时线速度 V x V_x Vx和角速度 w w w,需要计算四个轮子的线速度
v l f = w ⋅ ( V x w + t 2 ) 2 + ( L 2 2 ) + w ⋅ s v r f = w ⋅ ( V x w − t 2 ) 2 + ( L 2 2 ) − w ⋅ s p o s l f = L 2 V x w + t 2 p o s r f = L 2 V x w − t 2 \begin{aligned} v_{lf} = w \cdot \sqrt{\left( \frac{V_x}{w}+\frac{t}{2} \right)^2+\left( \frac{L}{2}^2 \right)}+w\cdot s \\ v_{rf} = w \cdot \sqrt{\left( \frac{V_x}{w}-\frac{t}{2} \right)^2+\left( \frac{L}{2}^2 \right)}-w\cdot s \end{aligned} \\ pos_{lf} = \frac{\frac{L}{2}}{\frac{V_x}{w}+\frac{t}{2}} \\ pos_{rf} = \frac{\frac{L}{2}}{\frac{V_x}{w}-\frac{t}{2}} vlf=w(wVx+2t)2+(2L2) +wsvrf=w(wVx2t)2+(2L2) wsposlf=wVx+2t2Lposrf=wVx2t2L

在这里插入图片描述

正相–模式2

每个车轮的线速度(除以车轮半径就是角速度):  v = ( v x 2 + v y 2 ) 每个车轮的转向:  p o s = tan ⁡ − 1 ( v y v x ) \begin{aligned}\\ \\ &\text {每个车轮的线速度(除以车轮半径就是角速度): }\\ &\begin{gathered} v=\sqrt{\left(v_x^2 + v_y^2\right)} \\ \end{gathered}\\ \\ &\text {每个车轮的转向: }\\ &\begin{gathered} p o s=\tan ^{-1}\left(\frac{v_y }{v_x}\right) \\ \end{gathered}\\ \end{aligned} 每个车轮的线速度(除以车轮半径就是角速度)v=(vx2+vy2) 每个车轮的转向pos=tan1(vxvy)

轴心–模式3

每个车轮的线速度(除以车轮半径就是角速度):  v l f = − v z v r f = v z 后轮和前轮同相。 每个车轮的转向:  p o s l f = − tan ⁡ − 1 ( b t ) p o s r f = tan ⁡ − 1 ( b t ) 后轮和前轮反相,后轮取负数即可。 \begin{aligned}\\ &\text {每个车轮的线速度(除以车轮半径就是角速度): }\\ &\begin{gathered} v_{lf} = -v_z \\ v_{rf} = v_z \\ \end{gathered}\\ &\text {后轮和前轮同相。}\\ \\ &\text {每个车轮的转向: }\\ &\begin{gathered} p o s_{lf}=-\tan ^{-1}\left(\frac{b}{t}\right) \\ p o s_{rf}=\tan ^{-1}\left(\frac{b}{t}\right) \\ \end{gathered}\\ &\text {后轮和前轮反相,后轮取负数即可。}\\ \end{aligned} 每个车轮的线速度(除以车轮半径就是角速度)vlf=vzvrf=vz后轮和前轮同相。每个车轮的转向poslf=tan1(tb)posrf=tan1(tb)后轮和前轮反相,后轮取负数即可。

本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。如若转载,请注明出处:http://www.xdnf.cn/news/148277.html

如若内容造成侵权/违法违规/事实不符,请联系一条长河网进行投诉反馈,一经查实,立即删除!

相关文章

如何快速免费搭建自己的Docker私有镜像源来解决Docker无法拉取镜像的问题(搭建私有镜像源解决群晖Docker获取注册表失败的问题)

文章目录 📖 介绍 📖🏡 演示环境 🏡📒 Docker无法拉取镜像 📒📒 解决方案 📒🔖 方法一:免费快速搭建自己的Docker镜像源🎈 部署🎈 使用🔖 备用方案⚓️ 相关链接 🚓️📖 介绍 📖 在当前的网络环境下,Docker镜像的拉取问题屡见不鲜(各类Nas查询…

意得辑(Editage)润色全网最低折扣

意得辑(Editage)润色全网最低折扣 优惠代码如图 可以点击我想要咨询~ 意得辑论文润色服务优惠代码|提高论文投稿成功率的最佳选择 推荐理由: 意得辑是全球领先的学术论文润色服务平台,特别适合非母语作者。凭借其专业的编辑团队…

买软件服务白送软件产品还送同等价值的白酒或其它商品,我这不是亏到姥姥家了吗?

原创 超云艾艾 AI智造AI编程 2024年09月23日 21:15 北京 在“企业数字化转型、建设和升级面临的主要难题和解决之道”文中,我提到过,针对企业做数字化转型和升级可能遇到的人才、资金和技术问题,我们可以基于SCSAI平台提供的十大功能以及多年…

巴黎嫩事件对数据信息安全的影响及必要措施

2024年9月17日,黎巴嫩首都贝鲁特发生了多起小型无线电通信设备爆炸事件,导致伊朗驻黎巴嫩大使受轻伤。这一事件不仅引发了对安全的广泛关注,也对数据信息安全提出了新的挑战。 王工 18913263502 对数据信息安全的影响: 数据泄露风…

颍川陈氏——平民崛起的典范

园子说颍川 广州有一处老建筑“陈家祠”,豪华精美堪比皇宫,誉为“岭南建筑艺术明珠”、“新世纪羊城八景”之一,是全国文保单位,4A 级景区。主体建筑以中轴线三座厅堂为中心,由大小十九座单体建筑组成,占地…

SpringBoot教程(三十) | SpringBoot集成Shiro权限框架

SpringBoot教程(三十) | SpringBoot集成Shiro权限框架 一、 什么是Shiro二、Shiro 组件核心组件其他组件 三、流程说明shiro的运行流程 四、SpringBoot 集成 Shiro (shiro-spring-boot-web-starter方式)1. 添加 Shiro 相关 maven2…

基于SpringBoot+Vue+MySQL的电影院购票管理系统

系统展示 用户前台界面 管理员后台界面 系统背景 随着电影产业的蓬勃发展,电影院已成为人们休闲娱乐的重要场所。然而,传统的电影院购票管理系统存在诸多不便,如购票流程繁琐、排队时间长、无法提前选座等问题,给观众的观影体验带…

计算机毕业设计之:微信小程序的校园闲置物品交易平台(源码+文档+讲解)

博主介绍: ✌我是阿龙,一名专注于Java技术领域的程序员,全网拥有10W粉丝。作为CSDN特邀作者、博客专家、新星计划导师,我在计算机毕业设计开发方面积累了丰富的经验。同时,我也是掘金、华为云、阿里云、InfoQ等平台…

计算机毕业设计 校园新闻管理系统的设计与实现 Java实战项目 附源码+文档+视频讲解

博主介绍:✌从事软件开发10年之余,专注于Java技术领域、Python人工智能及数据挖掘、小程序项目开发和Android项目开发等。CSDN、掘金、华为云、InfoQ、阿里云等平台优质作者✌ 🍅文末获取源码联系🍅 👇🏻 精…

隐匿发案:David律所代理艺术家Ina Tomecek的两张青蛙版权画维权

案件基本情况:起诉时间:2024-8-14案件号:2024-cv-07196原告:Ina Tomecek原告律所:Law Office of David Gulbransen起诉地:伊利诺伊州北部法院涉案商标/版权:原告品牌简介:Ina Tomece…

Qanything 2 0源码解析系列4 图片解析逻辑

Qanything 2.0源码解析系列4: 图片解析逻辑 文章转载自:https://www.feifeixu.top/article/8bb8401b-9689-453f-ab86-e3ecae414e12 😀 前言: 这篇文章介绍Qanything针对图片类型文件的处理逻辑 qanything_kernel/core/retriever/general_doc…

FreeMarker 禁止自动转义标签-noautoesc

💖简介 FreeMarker 是一个用 Java 语言编写的模板引擎,它被设计用来生成文本输出(HTML 网页、电子邮件、配置文件等)。在 FreeMarker 中,默认情况下,当你在模板中输出变量时,如果这些变量包含 …

shardingjdbc介绍

文章目录 1、shardingjdbc介绍1.1、读写分离、数据分片(分库分表)中间件:1.1.1、shardingsphere1.1.2、mycat 2、shardingjdbc-demo搭建2.1、创建项目2.2、添加依赖2.3、application.yml2.4、创建实体类 User2.5、创建 UserMapper2.6、创建测…

DNA亲和纯化测序(DAP-seq)、组蛋白甲基化修饰(H3K4me3 ChlP-seq)

🌟 教授团队领衔,全方位服务! 🚀 从实验设计到论文发表,一站式解决方案! 📈 选择我们,加速您的科研进程,让成果不再等待! 📝 专业分析 定制服…

19_Python中的上下文管理器

Python中的上下文管理器 在Python中,上下文管理器(Context Manager)是一种用于资源管理的技术,它可以确保资源在使用后被正确释放,例如文件、网络连接或锁。 上下文管理器(Context Manager)是…

GB28181语音对讲协议详解

GB28181-2016语音对讲流程如下图1所示: 图1.语音对讲流程。 其中, 信令 1 、2 、 3 、 4 为语音广播通知、 语音广播应答消息流程; 信令 5 、 1 2 、 1 3 、 1 4 、 1 5 、 1 6 为 S I P 服务器接收到客户端的呼叫请求通过 B 2 B UA 代理方式建立语音流接收者与媒…

计算机毕业设计之:基于微信小程序的电费缴费系统(源码+文档+讲解)

博主介绍: ✌我是阿龙,一名专注于Java技术领域的程序员,全网拥有10W粉丝。作为CSDN特邀作者、博客专家、新星计划导师,我在计算机毕业设计开发方面积累了丰富的经验。同时,我也是掘金、华为云、阿里云、InfoQ等平台…

MatrixOne助力一道创新打造高性能智能制造AIOT系统

客户简介 深圳一道创新(ETAO Innovation)成立于2012年,是一家创新型软件及信息技术服务商,致力于制造戏份行业—电子制造业的数字转型服务,构建万物互联的智能工程。一道创新致力于把先进的软件系统、数字平台、人工智…

QT中添加资源文件

什么是资源文件 项目中经常需要添加图片、‌音频、‌视频、翻译文件等文件,在QT中,这些文件会放在 .qrc 文件中来被使用。 .qrc 文件是一个XML格式的资源集合描述文件,是Qt中用于定义和管理资源的关键文件 如何使用 创建资源文件 在你的Qt项…

C++之STL—string容器

本质:类 class 封装了很多方法:查找find,拷贝copy,删除delete 替换replace,插入insert 构造函数 赋值操作 assign: 字符串拼接 + append: string查找和替换 没查找到,po…