阿克曼底盤的URDF建模與Gazebo控制(使用Xacro優化)
阿克曼底盤建模
建模
我們使用后輪驅動,前輪轉向的阿克曼底盤模型。
那么對于后輪只需進行正常的continous joint
連接即可
對于前輪,有兩個自由度,旋轉和轉向,而且由于URDF
無法進行閉鏈關節建模,因此我們模擬一個轉向桿,使用revolute joint
限定轉向角度首先將base_link
與轉向桿連接,之后使用continous joint
將轉向桿與車輪相連。
如下為具體實現:
<robot name="akeman_base" xmlns:xacro="http://www.ros.org/wiki/xacro"><xacro:property name="PI" value="3.1415926" /><xacro:property name="wheel_radius" value="0.03" /><xacro:property name="wheel_height" value="0.02" /><xacro:property name="wheel_in" value="0.0125" /><xacro:property name="base_linkheight" value="0.075" /><xacro:property name="base_length" value="0.225" /><xacro:property name="base_width" value="0.2" /><xacro:property name="base_height" value="0.01" /><link name="base_footprint"><visual><geometry><sphere radius="0.001" /></geometry><origin xyz="0 0 0" rpy="0 0 0" /><material name="yellow"><color rgba="0.8 0.3 0.1 0.5" /></material> </visual></link><link name="base_link"><visual><geometry><box size="${base_length} ${base_width} ${base_linkheight}" /></geometry><origin xyz="0 0 0" rpy="0 0 0" /><material name="blue"><color rgba="0 0 1.0 0.5" /></material></visual></link><joint name="base_link2base_footlink" type="fixed"><parent link="base_footprint" /><child link="base_link" /><origin xyz="0 0 ${base_height}" rpy="0 0 0" /></joint><xacro:macro name="define_rear_wheel" params="name flag"><link name="${name}_rear_wheel"><visual><geometry><cylinder radius="${wheel_radius}" length="${wheel_height}" /></geometry><origin xyz="0 0 0" rpy="${flag*PI/2} 0 0" /><material name="yellow"><color rgba="0.8 0.3 0.1 0.5" /></material></visual></link><joint name="${name}_rear_wheel2base_link" type="continuous"><parent link="base_link" /><child link="${name}_rear_wheel" /><origin xyz="${-(-wheel_in-wheel_radius+base_length/2)} ${flag*(wheel_height/2 + base_width/2)} ${-(base_linkheight/2+base_height-wheel_radius)}" /><axis xyz="0 1 0" /></joint></xacro:macro><xacro:define_rear_wheel name="left" flag="1" /><xacro:define_rear_wheel name="right" flag="-1" /><xacro:macro name="define_front_wheel" params="name flag"><link name="${name}_front_wheel"><visual><geometry><cylinder radius="${wheel_radius}" length="${wheel_height}" /></geometry><origin xyz="0 0 0" rpy="${flag*PI/2} 0 0" /><material name="yellow"><color rgba="0.8 0.3 0.1 0.5" /></material></visual></link><link name="${name}_steer_front_joint"><visual><geometry><box size="0.01 0.01 0.01" /></geometry><origin xyz="0 0 0" rpy="0 0 0" /><material name="black"><color rgba="0.7 0.5 0 0.5" /></material></visual></link><joint name="${name}_steer_front_joint2base_link" type="revolute"><parent link="base_link" /><child link="${name}_steer_front_joint" /><origin xyz="${-wheel_in-wheel_radius+base_length/2} ${flag*(wheel_height/2 + base_width/2)} ${0.01 + base_linkheight/2}" /><axis xyz="0 0 1" /><limit lower="-0.69" upper="0.69" effort="0" velocity="3"/></joint><joint name="${name}_front_wheel2${name}_steer_front_joint" type="continuous"><parent link="${name}_steer_front_joint" /><child link="${name}_front_wheel" /><origin xyz="0 0 ${-(0.01+base_linkheight+base_height-wheel_radius)}" /><axis xyz="0 1 0" /></joint></xacro:macro><xacro:define_front_wheel name="left" flag="1" /><xacro:define_front_wheel name="right" flag="-1" /></robot>
效果
如下圖,可以看到前輪可以通過GUI
旋轉steer_link
實現轉向
URDF集成Gazebo
較之于 rviz
,gazebo
在集成 URDF
時,需要做些許修改:
- 必須添加
collision
碰撞屬性相關參數 - 必須添加
inertial
慣性矩陣相關參數 Gazebo
顏色設置也必須做相應的變更
collision 碰撞屬性
如果機器人link
是標準的幾何體形狀,和link
的visual
屬性設置一致即可,但沒有顏色屬性
inertial 慣性矩陣
對于標準幾何體的慣性矩陣,有標準公式,因此我們可以使用一個專門的Xacro
文件利用宏封裝這些標準幾何體的慣性矩陣的公式,之后在其他Xacro
文件中包含并調用即可;
<robot name="base" xmlns:xacro="http://wiki.ros.org/xacro"><!-- Macro for inertia matrix 球體 圓柱體 立方體--><xacro:macro name="sphere_inertial_matrix" params="m r"><inertial><mass value="${m}" /><inertia ixx="${2*m*r*r/5}" ixy="0" ixz="0"iyy="${2*m*r*r/5}" iyz="0" izz="${2*m*r*r/5}" /></inertial></xacro:macro><xacro:macro name="cylinder_inertial_matrix" params="m r h"><inertial><mass value="${m}" /><inertia ixx="${m*(3*r*r+h*h)/12}" ixy = "0" ixz = "0"iyy="${m*(3*r*r+h*h)/12}" iyz = "0"izz="${m*r*r/2}" /> </inertial></xacro:macro><xacro:macro name="Box_inertial_matrix" params="m l w h"><inertial><mass value="${m}" /><inertia ixx="${m*(h*h + l*l)/12}" ixy = "0" ixz = "0"iyy="${m*(w*w + l*l)/12}" iyz= "0"izz="${m*(w*w + h*h)/12}" /></inertial></xacro:macro>
</robot>
顏色設置
在Gazebo
中顯示link
的顏色,必須指定標簽,使用如下指令,該指令與link
平級
<gazebo reference="link節點名稱"><material>Gazebo/Blue</material>
</gazebo>
URDF在Gazebo下可視化
<launch><!-- 將 Urdf 文件的內容加載到參數服務器 --><param name="robot_description" command="$(find xacro)/xacro $(find urdf_rviz)/urdf/xacro/akeman_base.xacro" /><!-- 啟動 gazebo --><include file="$(find gazebo_ros)/launch/empty_world.launch" /><!-- 在 gazebo 中顯示機器人模型 --><node pkg="gazebo_ros" type="spawn_model" name="model" args="-urdf -model akemanbase -param robot_description" />
</launch>
Gazebo與ROS_control
在前面Rviz
中,我們使用了joint_state_publisher_gui
節點來控制關節的轉動,但是也只是轉動,沒有任何的物理屬性,例如我們轉動車輪關節,小車并不會移動。Gazebo
相對于Rviz
的優點也在于此,Gazebo
有真實的物理引擎,可以通過給關節加入傳動裝置實現運動控制。
具體使用Gazebo
仿真,我們借助ROS_Control
軟件包實現,其工作流圖下圖可以很好的展現(源自ROS wiki):
其主要由以下幾部分組成:
Controller Manager
控制器管理器:管理不同控制器的通用接口Controller
控制器:讀取硬件資源接口中的狀態,運行PID等控制器發布控制指令。不直接接觸硬件,也從硬件抽象層請求讀取資源RobotHW
機器人硬件抽象:可以直接和硬件資源交互,通過write
和read
方法完成硬件操作。管理硬件資源,處理硬件沖突Hardware Resource
硬件資源:提供硬件資源的接口,包含硬件關節限制、傳動機構等,我們配置傳動機構實際就是配置硬件資源
傳動裝置Transmission的添加
傳動系統用于將機器人的關節指令轉換成執行器的控制信號,可在機器人的URDF
模型文件中配置。下面為一個Transmission
的示例:
<transmission name="trans_name" > <type>transmission_interface/SimpleTransmission</type><joint name="foo_joint"><hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface></joint><actuator name="foo_motor"><mechanicalReduction>50</mechanicalReduction><hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface></actuator>
</transmission>
<transmission name="trans_name" >
定義傳動機構名稱<joint name="foo_joint">
指定傳動裝置對應關節<hardwareInterface>
定義硬件接口,選用力關節接口即可
<actuator name="foo_motor">
定義傳動執行器<mechanicalReduction>50</mechanicalReduction>
定義了電機/關節減速比<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
定義了支持的硬件接口,包含力、速度hardware_interface/VelocityJointInterface
、位置hardware_interface/PositionJointInterface
。<motorTorqueConstant>
(可選)定義了電機的轉矩參數
在我們的阿克曼小車模型中,我們需要對后輪增加兩個旋轉電機,前輪增加兩個舵機控制角度。對應的關節分別為${name}_rear_wheel2base_link
和${name}_front_wheel2${name}_steer_front_joint
。
加入傳動裝置后,我們還需要加入插件進行gazebo
和ros_control
的對接,gazebo_ros_control
是Gazebo
的一個插件用來根據設定裝載合適的硬件接口和控制器。示例如下:
<gazebo><plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so"><robotNamespace></robotNamespace><robotParam>robot_description</robotParam><robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType><legacyModeNS>true</legacyModeNS></plugin>
</gazebo>
<robotNamespace>
用來定義插件其對象的ROS命名空間,默認是URDF或者SDF對應的機器人名稱。<contolPeriod>
用來定義控制器的更新周期,單位為秒,默認使用Gazebo的周期。<robotParam>
用來定義ROS參數服務器上的機器人描述(URDF)路徑,默認是"/robot_description"。<robotSimType>
用來定義機器人仿真接口所使用的插件庫名稱,默認是"DefaultRobotHWSim"。<legacyModeNS>
用來兼容之前ROS版本的配置。
另外,也可以添加屬性reference
,這樣它就是對整個機器人<robot>
的描述。
Controller 控制器
對于Akermann小車,我們可以借助ros-controllers
軟件包下的ackermann_steering_controller
來實現,但需要額外安裝,運行以下指令即可。
sudo apt-get install ros-noetic-ros-control ros-noetic-ros-controllers
此外,steer_bot_hardware_gazebo
支持四輪控制器,但該軟件包最高只支持到了melodic
版本(可以在github
查閱下載編譯),本人使用的是noetic
版本,所以無法安裝。
如果使用魚香ROS一鍵安裝,則需要再次使用一鍵安裝中的配置系統源中重新配置更換系統源和加入ROS源。
查閱ROS wiki,可以發現ackermann_steering_controller
僅支持前后兩個輪的小車模型,因此我們需要對模型進行一定的修改,方便進行控制。
在兩后輪之間加入一個虛擬輪,該虛擬后輪首先與基座之間形成continous joint
,再和兩個后輪分別形成continous joint
,此時旋轉虛擬后輪則相當于旋轉兩個后輪。
將前向的兩個模擬轉向關節合為一個,旋轉合并后的關節就相當于同時進行兩個輪轉向。
這個方法太過逆天,實際上并不適合實際的仿真系統,故舍棄!!!
為了更貼合真實情況,我們還是為兩個前輪都加入了轉向關節,并為能夠在gazebo
中正常顯示,進行了適應性修改。
ros_control
功能包提供的控制器有許多,以下為案例:
在ros_controllers
的wiki
中可以發現更多:
Gazebo建模中出現的問題,以及如何解決
問題1:輪子陷入地面!
首先檢查,base_link
和base_footprint
之間的距離是否合理
其次,車輪的collision
中的origin
和visual
中的是否相同,尤其是旋轉RPY
一定要檢查!
問題2:小車歪七八扭?
- 檢查小車的物理特性是否合理,例如重力上是否可以讓車輪支撐底座(Gazebo是一個物理仿真平臺,因此一定要注意這一點)
- 慣性矩陣問題,是否出現賦予錯的慣性矩陣?
- 車輪的
visual
屬性和collision
屬性是否保持一致,不要忘記PI/2
問題3:如何讓一個物體和另一個物體連接在一起?并且我們希望二者中間存在一個自由度?
Gazebo
中,我們只需要在建模時,讓兩者的位置嵌合在一起,就可以保證二者不會因為重力而分離
問題4:revolute
關節晃來晃去?
對該關節增加阻尼:
<dynamics damping="0.5" />
關于關節?
joints
的作用不僅可以在link
之間建立運動關系,同時還會把他們鏈接成一個整體,相當于現實中的螺絲連接等方式。
多次迭代優化后可以在Gazebo中穩定的阿克曼小車底盤
<?xml version="1.0" ?>
<robot name="ackermann_base_final" xmlns:xacro="http://www.ros.org/wiki/xacro"><!-- 參數 --><xacro:property name="PI" value="3.1415926" /><!-- 車輪參數 --><xacro:property name="wheel_radius" value="0.04" /><xacro:property name="wheel_height" value="0.03" /><xacro:property name="wheel_in" value="0.0125" /><!-- 基座參數 --> <xacro:property name="base_height" value="0.075" /><xacro:property name="base_length" value="0.275" /><xacro:property name="base_width" value="0.2" /><!-- 車輪參數 --><xacro:property name="steering_link_length" value="0.02" /> <xacro:property name="steering_link_width" value="0.06" /><xacro:property name="steering_link_height" value="0.02" /><!-- 基座離地高度 --><xacro:property name="base_ground_clearance" value="0.02" /><!-- 質量參數 --><xacro:property name="base_m" value="2" /><xacro:property name="wheel_m" value="0.5" /> <xacro:property name="steering_link_m" value="0.05" /> <xacro:include filename="inertial_matrix.xacro"/><link name="base_footprint"><visual><origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/><geometry><sphere radius="0.001"/></geometry><material name="yellow"><color rgba="0.8 0.3 0.1 0.5" /></material> </visual><collision><origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/><geometry><sphere radius="0"/></geometry></collision></link><link name="base_link"><xacro:Box_inertial_matrix m="${base_m}" l="${base_length}" w="${base_width}" h="${base_height}" /><visual><origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/><geometry><box size="${base_length} ${base_width} ${base_height}"/></geometry><material name="blue"><color rgba="0 0 1.0 0.5" /></material></visual><collision><origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/><geometry><box size="0 0 0"/></geometry></collision></link><gazebo reference="base_link"><material>Gazebo/Blue</material></gazebo><joint name="base_link2base_footprint" type="fixed"><parent link="base_footprint"/><child link="base_link"/><origin xyz="0.0 0.0 ${base_ground_clearance+base_height/2+0.001}" rpy="0.0 0.0 0.0"/></joint><xacro:macro name="define_steer_joint" params="name flag"><link name="${name}_steer_link"><xacro:Box_inertial_matrix m="${steering_link_m}" l="${steering_link_length}" w="${steering_link_width}" h="${steering_link_height}" /><visual><origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/><geometry><box size="${steering_link_length} ${steering_link_width} ${steering_link_height}"/></geometry></visual><collision><origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/><geometry><box size="0 0 0"/></geometry></collision></link><joint name="${name}_steer_link2base_link" type="revolute"><origin xyz="${base_length/2-wheel_in-wheel_radius} ${flag*(base_width/2-steering_link_width/2)} ${-(base_height/2 + base_ground_clearance - wheel_radius)}" rpy="0.0 0.0 0.0"/><parent link="base_link"/><child link="${name}_steer_link"/><axis xyz="0 0 1"/><dynamics damping="0.1" /><limit lower="-0.6" upper="0.6" effort="0" velocity="3"/></joint><gazebo reference="${name}_steer_link"><material>Gazebo/Yellow</material></gazebo></xacro:macro><xacro:define_steer_joint name="left" flag="1" /><xacro:define_steer_joint name="right" flag="-1" /><xacro:macro name="define_front_joint" params="name flag"><link name="${name}_front_wheel"><xacro:cylinder_inertial_matrix m="${wheel_m}" r="${wheel_radius}" h="${wheel_height}" /><visual><origin xyz="0.0 0.0 0.0" rpy="${-PI/2} 0.0 0.0"/><geometry><cylinder radius="${wheel_radius}" length="${wheel_height}"/></geometry></visual><collision><origin xyz="0.0 0.0 0.0" rpy="${-PI/2} 0.0 0.0"/><geometry><cylinder radius="${wheel_radius}" length="${wheel_height}"/></geometry></collision></link><gazebo reference="${name}_front_wheel"><material>Gazebo/Yellow</material></gazebo><gazebo reference="${name}_front_wheel"><mu1>0.6</mu1> <!-- 顯著降低靜摩擦 --><mu2>0.9</mu2> <!-- 降低動摩擦 --></gazebo> <joint name="${name}_front_wheel2${name}_steer_link" type="continuous"><origin xyz="0 0 0.0" rpy="0.0 0.0 0.0"/><parent link="${name}_steer_link"/><child link="${name}_front_wheel"/><axis xyz="0 1 0"/></joint></xacro:macro><xacro:define_front_joint name="left" flag="1" /><xacro:define_front_joint name="right" flag="-1" /><xacro:macro name="define_rear_joint" params="name flag"><link name="${name}_rear_link"><xacro:Box_inertial_matrix m="${steering_link_m}" l="${steering_link_length}" w="${steering_link_width}" h="${steering_link_height}" /><visual><origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/><geometry><box size="${steering_link_length} ${steering_link_width} ${steering_link_height}"/></geometry></visual><collision><origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/><geometry><box size="0 0 0"/></geometry></collision></link><link name="${name}_rear_wheel"><xacro:cylinder_inertial_matrix m="${wheel_m}" r="${wheel_radius}" h="${wheel_height}" /><visual><origin xyz="0.0 0.0 0.0" rpy="${-PI/2} 0.0 0.0"/><geometry><cylinder radius="${wheel_radius}" length="${wheel_height}"/></geometry></visual><collision><origin xyz="0.0 0.0 0.0" rpy="${-PI/2} 0.0 0.0"/><geometry><cylinder radius="${wheel_radius}" length="${wheel_height}"/></geometry></collision></link><gazebo reference="${name}_rear_wheel"><mu1>1.8</mu1> <!-- 大幅提高靜摩擦 --><mu2>1.2</mu2> <!-- 提高動摩擦 --></gazebo> <joint name="${name}_rear_link2base_link" type="fixed"><origin xyz="${-base_length/2+wheel_in+wheel_radius} ${flag*(base_width/2-steering_link_width/2)} ${-(base_height/2 + base_ground_clearance - wheel_radius)}" rpy="0.0 0.0 0.0"/><parent link="base_link"/><child link="${name}_rear_link"/></joint><joint name="${name}_rear_wheel2${name}_rear_link" type="continuous"><origin xyz="0 0 0.0" rpy="0.0 0.0 0.0"/><parent link="${name}_rear_link"/><child link="${name}_rear_wheel"/><axis xyz="0 1 0"/></joint><gazebo reference="${name}_rear_wheel"><material>Gazebo/Yellow</material></gazebo></xacro:macro><xacro:define_rear_joint name="left" flag="1" /><xacro:define_rear_joint name="right" flag="-1" /><xacro:macro name="define_wheel_trans" params="left_right front_rear steer_rear"><transmission name="${left_right}_${front_rear}_wheel_trans"><type>transmission_interface/SimpleTransmission</type><joint name="${left_right}_${front_rear}_wheel2${left_right}_${steer_rear}_link"><hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface></joint><actuator name="${left_right}_${front_rear}_wheel_actuator"><mechanicalReduction>1.0</mechanicalReduction><hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface></actuator></transmission></xacro:macro><xacro:macro name="define_steer_trans" params="left_right"><transmission name="${left_right}_steer_trans"><type>transmission_interface/SimpleTransmission</type><joint name="${left_right}_steer_link2base_link"><hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface></joint><actuator name="${left_right}_steer_actuator"><mechanicalReduction>1.0</mechanicalReduction><hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface></actuator></transmission></xacro:macro><xacro:define_wheel_trans left_right="left" front_rear="rear" steer_rear="rear" /><xacro:define_wheel_trans left_right="right" front_rear="rear" steer_rear="rear" /><xacro:define_steer_trans left_right="left" /><xacro:define_steer_trans left_right="right" /><gazebo><plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so"><robotNamespace>ackermann_base_final</robotNamespace><robotParam>robot_description</robotParam><robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType><legacyModeNS>true</legacyModeNS><robotBaseFrame>base_footprint</robotBaseFrame> </plugin></gazebo><gazebo reference="base_footprint"><turnGravityOff>true</turnGravityOff></gazebo></robot>
加入傳動裝置:
<xacro:macro name="define_wheel_trans" params="left_right front_rear steer_rear"><transmission name="${left_right}_${front_rear}_wheel_trans"><type>transmission_interface/SimpleTransmission</type><joint name="${left_right}_${front_rear}_wheel2${left_right}_${steer_rear}_link"><hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface></joint><actuator name="${left_right}_${front_rear}_wheel_actuator"><mechanicalReduction>1.0</mechanicalReduction><hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface></actuator></transmission></xacro:macro><xacro:macro name="define_steer_trans" params="left_right"><transmission name="${left_right}_steer_trans"><type>transmission_interface/SimpleTransmission</type><joint name="${left_right}_steer_link2base_link"><hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface></joint><actuator name="${left_right}_steer_actuator"><mechanicalReduction>1.0</mechanicalReduction><hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface></actuator></transmission></xacro:macro><xacro:define_wheel_trans left_right="left" front_rear="rear" steer_rear="rear" /><xacro:define_wheel_trans left_right="right" front_rear="rear" steer_rear="rear" /><xacro:define_steer_trans left_right="left" /><xacro:define_steer_trans left_right="right" /><gazebo><plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so"><robotNamespace>ackermann_base_final</robotNamespace><robotParam>robot_description</robotParam><robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType><legacyModeNS>true</legacyModeNS><robotBaseFrame>base_footprint</robotBaseFrame> </plugin></gazebo>
最終建模效果:
阿克曼小車的控制器設置yaml
值得注意的是,我們沒有在前輪的兩個轉動輪上加入電機,這是因為一旦加入傳動裝置,該關節的從動屬性將消失,無法被后輪從動。
ackermann_base_final:joint_state_controller:type: "joint_state_controller/JointStateController"publish_rate: 50left_steer_controller:type: "position_controllers/JointPositionController"joint: left_steer_link2base_linkright_steer_controller:type: "position_controllers/JointPositionController"joint: right_steer_link2base_linkleft_rear_wheel_controller:type: "velocity_controllers/JointVelocityController"joint: left_rear_wheel2left_rear_linkright_rear_wheel_controller:type: "velocity_controllers/JointVelocityController"joint: right_rear_wheel2right_rear_link
啟動Gazebo的launch文件
<launch><!-- 將 Urdf 文件的內容加載到參數服務器 --><param name="robot_description" command="$(find xacro)/xacro $(find urdf_rviz)/urdf/xacro/ackermann_base_final.xacro" /><!-- 啟動 gazebo --><include file="$(find gazebo_ros)/launch/empty_world.launch" /><!-- 在 gazebo 中顯示機器人模型 --><node pkg="gazebo_ros" type="spawn_model" name="model" args="-urdf -model ackermann_base_final -param robot_description" /><!-- 加載控制器參數 --><rosparam file="$(find urdf_rviz)/config/rviz/ackermann/ackermann_base_final.yaml" command="load"/><node name="controller_spawner" pkg="controller_manager" type="spawner" output="screen"ns="/ackermann_base_final"args="joint_state_controllerleft_steer_controllerright_steer_controllerleft_rear_wheel_controllerright_rear_wheel_controller" /></launch>`
問題解決:
[ERROR] Could not load controller ‘right_steer_controller’ because the type was not specified.
這個就是因為在yaml中,我們為機器人命了名,為ackermann_base_final
,所以所有控制器都在該命名空間下,所以要在加載controller_manager
時,設定ns="/controller_manager"
<node name="controller_spawner" pkg="controller_manager" type="spawner" output="screen"ns="/ackermann_base_final"args="joint_state_controllerleft_steer_controllerright_steer_controllerleft_rear_wheel_controllerright_rear_wheel_controller" />
[WARN] Controller Spawner couldn’t find the expected controller_manager ROS interface.
可以看到我們在yaml
中指定輪命名空間,所以在gazebo
加載插件時也要聲明命名空間!所以改為:
<gazebo><plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so"><robotNamespace>ackermann_base_final</robotNamespace><robotParam>robot_description</robotParam><robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType><legacyModeNS>true</legacyModeNS></plugin>
</gazebo>
[ERROR] Exception thrown while initializing controller ‘right_rear_wheel_controller’.Could not find resource ‘right_rear_wheel2right_rear_link’ in ‘hardware_interface::EffortJointInterface’.
由于我們在定義transmission
時,使用的hardware_interface/PositionJointInterface
,那么對應的控制器也應該為position_controllers/JointPositionController
,保證能夠實現接口的對應。相應的,PositionJointInterface
對應position_controllers
,VelocityJointInterface
對應velocity_controllers
。
[ERROR] No p gain specified for pid. Namespace: /gazebo_ros_control/pid_gains/left_front_wheel2left_steer_link
提示我們沒有為其配置PID
,實際上我們可以忽略該信息,因為可能配置的還不如系統自動的,該信息源自于小魚ROS論壇
小車車輪空轉?
檢查base_footprint的實體collision屬性是否關閉,若沒有關閉則小車將被架在base_footprint上
驗證
launch后,運行以下bash文件,可以看到阿克曼小車繞圓運行
# 設置前輪轉向角為 0.5 rad(約 28.6 度)
rostopic pub /ackermann_base_final/left_steer_controller/command std_msgs/Float64 "data: 0.47"&rostopic pub /ackermann_base_final/right_steer_controller/command std_msgs/Float64 "data: 0.5"&rostopic pub /ackermann_base_final/left_rear_wheel_controller/command std_msgs/Float64 "data: 5"&rostopic pub /ackermann_base_final/right_rear_wheel_controller/command std_msgs/Float64 "data: 5"
傳感器
IMU
IMU
測量物體三軸姿態角(或角速率)以及加速度的裝置,在機器人導航中有著很重要的應用。在Gazebo
仿真中,我們可以直接將imu
插件附加在base_link
上。只需要在URDF中加入這段即可。
<gazebo reference="base_link"><gravity>true</gravity><sensor name="imu_sensor" type="imu"><always_on>true</always_on><update_rate>100</update_rate><visualize>true</visualize><topic>__default_topic__</topic><plugin filename="libgazebo_ros_imu_sensor.so" name="imu_plugin"><robotNamespace>ackermann_base_final</robotNamespace><topicName>imu</topicName><bodyName>base_link</bodyName><updateRateHZ>100.0</updateRateHZ><gaussianNoise>0.0</gaussianNoise><xyzOffset>0 0 0</xyzOffset><rpyOffset>0 0 0</rpyOffset><frameName>imu_link</frameName></plugin><pose>0 0 0 0 0 0</pose></sensor>
</gazebo>
加入后運行時,在命令行輸入rostopic
會出現/ackermann_base_final/imu
的話題,我們可以利用rqt_plot
工具展現數據。例如我們使用其訂閱/ackermann_base_final/imu/orientation
可以觀察小車的航向角變化。例如我們運行先前的繞圓運行bash
文件,觀察rqt_plot
可以發現其成正弦波形式,說明小車在繞圓運行。
rqt_plot
使用tips:
- 左上角第五個像放大鏡的東西點擊后,左鍵框選區域放大,右鍵縮小
- 若橫軸或縱軸步距過長,可以通過左上角倒數第二個功能進行橫坐標和縱坐標展現范圍的改變