重头开始学ROS(5)---阿克曼底盘的URDF建模与Gazebo控制(使用Xacro优化)

阿克曼底盘的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

较之于 rvizgazebo在集成 URDF 时,需要做些许修改:

  1. 必须添加collision碰撞属性相关参数
  2. 必须添加 inertial 惯性矩阵相关参数
  3. Gazebo颜色设置也必须做相应的变更

collision 碰撞属性

如果机器人link是标准的几何体形状,和linkvisual属性设置一致即可,但没有颜色属性

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 机器人硬件抽象:可以直接和硬件资源交互,通过 writeread 方法完成硬件操作。管理硬件资源,处理硬件冲突
  • 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
      加入传动装置后,我们还需要加入插件进行gazeboros_control的对接,gazebo_ros_controlGazebo的一个插件用来根据设定装载合适的硬件接口和控制器。示例如下:
<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_controllerswiki中可以发现更多:
在这里插入图片描述

Gazebo建模中出现的问题,以及如何解决

问题1:轮子陷入地面!

首先检查,base_linkbase_footprint之间的距离是否合理
其次,车轮的collision中的originvisual中的是否相同,尤其是旋转RPY一定要检查!

问题2:小车歪七八扭?

在这里插入图片描述

  1. 检查小车的物理特性是否合理,例如重力上是否可以让车轮支撑底座(Gazebo是一个物理仿真平台,因此一定要注意这一点)
  2. 惯性矩阵问题,是否出现赋予错的惯性矩阵?
  3. 车轮的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_controllersVelocityJointInterface对应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:

  1. 左上角第五个像放大镜的东西点击后,左键框选区域放大,右键缩小
  2. 若横轴或纵轴步距过长,可以通过左上角倒数第二个功能进行横坐标和纵坐标展现范围的改变

激光雷达

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

如若内容造成侵权/违法违规/事实不符,请联系多彩编程网进行投诉反馈email:809451989@qq.com,一经查实,立即删除!

相关文章

RabbitMq中启用NIO

✅ 所属类 com.rabbitmq.client.ConnectionFactory&#x1f9e0; 使用背景 RabbitMQ Java 客户端默认使用传统的 阻塞 I/O (java.net.Socket) 实现。如果你希望&#xff1a; 更好地控制 线程数获得更好的 并发性能降低 每个连接的线程占用在高并发连接或消费者数量较多的系统…

[Dify]-基础篇2- 如何注册并快速上手 Dify 平台

在生成式 AI 应用开发新时代,如何快速搭建一个高效、可维护、易上线的 AI 工具,是每位开发者关注的核心。Dify,正是为此而生的一站式平台。本篇将以新手视角,带你从注册账号、配置环境,到构建应用、部署上线,手把手完成你的第一个 AI 项目。 注册并设置工作环境 1. 账号…

Java面试宝典:基础七

153. 如何实现对象克隆? 答: 对象克隆有两种主要方式: 浅克隆:实现Cloneable接口并重写Object.clone() class Person implements Cloneable {String name;Car car; // 引用类型@Override

spring-security原理与应用系列:requestMatchers和authorizeRequests

目录 简单示例 WebSecurityConfig requestMatchers ​​​​​​​requestMatchers ​​​​​​​antMatchers ​​​​​​​chainRequestMatchers ​​​​​​​setMatchers ​​​​​​​requestMatcher ​​​​​​​WebSecurity ​​​​​​​performBuild…

Bessel位势方程求解步骤

问题 考虑偏微分方程&#xff08;PDE&#xff09;&#xff1a; − Δ u u f , x ∈ R n , -\Delta u u f, \quad x \in \mathbb{R}^n, −Δuuf,x∈Rn, 其中 f ∈ L 2 ( R n ) f \in L^2(\mathbb{R}^n) f∈L2(Rn)。这是一个线性椭圆型方程&#xff0c;称为 Bessel 位势方…

if __name__ == ‘__main__‘:

基本概念 if __name__ __main__: 是一个条件判断语句&#xff0c;用于确定当前模块是作为主程序运行&#xff0c;还是被其他模块导入。 __name__ 变量 __name__ 是Python的一个内置变量&#xff0c;表示当前模块的名称当一个模块被直接运行时&#xff0c;__name__ 的值会被…

浅谈Apache HttpClient的相关配置和使用

Apache HttpClient是由Apache软件基金会维护的一款开源HTTP客户端库&#xff0c;对比最基础的 HttpURLConnection 而言,它的优势时支持连接池管理&#xff0c;拦截器&#xff08;Interceptor&#xff09;机制&#xff0c;同步/异步请求支持等能力。 在使用这个组件时&#xff…

【Teensy】在ArduinoIDE中配置Teensy4.1

1.文件——首选项 在其他开发板管理器地址这里添加&#xff1a; https://www.pjrc.com/teensy/package_teensy_index.json 点击确定&#xff01; 2.安装Teensy(for Arduino IDE…) 按照图中1&#xff0c;2&#xff0c;3操作&#xff01;可以选择上一个版本&#xff08;不使用最…

企业自建云概念解读|私有云、专有云、混合云、分布式云、企业云

随着云计算技术逐渐成熟&#xff0c;越来越多的企业开始在本地数据中心自行搭建云平台&#xff0c;满足数据合规、业务性能与连续性、节约成本等多方面的需求。不过&#xff0c;面对多种多样的自建云产品&#xff0c;不少用户会有类似的疑问&#xff1a;自建云等于私有云吗&…

反弹 Shell 升级为全交互终端的两种高效方法

目录 🚀 升级反弹 Shell 为全交互终端:两种高效方法 🛠️ 方法 1:利用 Python pty.spawn 创建伪终端 📋 操作步骤

Hyper-YOLO: When Visual Object Detection Meets Hypergraph Computation论文精读(逐段解析)

Hyper-YOLO: When Visual Object Detection Meets Hypergraph Computation论文精读&#xff08;逐段解析&#xff09; 论文地址&#xff1a;https://arxiv.org/abs/2408.04804 CVPR 2024 Yifan Feng, Jiangang Huang, Shaoyi Du, Senior Member, IEEE, Shihui Ying, Jun-Hai Y…

Windows 下配置多个 GitHub 账号的 SSH Key

Windows 下配置多个 GitHub 账号的 SSH Key 假设你有以下两个 SSH key 文件&#xff1a; 第一个账号&#xff1a;id_rsa&#xff08;默认&#xff09;第二个账号&#xff1a;id_rsa_github ✅ 步骤&#xff1a;在 Windows 上配置多个 GitHub 账号 SSH Key 1️⃣ 打开 SSH 配…

技术选型:时序数据库(三)

IoTDB vs InfluxDB vs TDengine 时序数据库横评对比。 从 架构设计、性能、功能、生态、适用场景 等维度&#xff0c;对三款时序数据库进行深度对比&#xff0c;助您精准选型。 一、核心架构对比 数据库 存储模型 数据模型 扩展性 Apache IoTDB 分层存储&#xff08;TsFi…

电子电路原理第十九章(非线性运算放大器电路的应用)

单片集成运算放大器价格便宜、用途广泛且性能可靠。它们不仅可以用于线性电路,如电压放大器、电流源和有源滤波器,而且可以用于非线性电路,如比较器、波形生成器和有源二极管电路。非线性运放电路的输出通常与输入信号的波形不同,这是因为运放在输入周期的某个时间段内达到…

FPGA实现CameraLink视频解码转SDI输出,基于LVDS+GTX架构,提供2套工程源码和技术支持

目录 1、前言工程概述免责声明 2、CameraLink协议理论学习3、相关方案推荐我已有的所有工程源码总目录----方便你快速找到自己喜欢的项目FPGA实现CameraLink视频编解码方案本博已有的 SDI 编解码方案 4、工程详细设计方案工程设计原理框图输入CameraLink相机LVDS视频解码模块LV…

户外人像要怎么拍 ?

前言&#xff1a; ” 接上篇&#xff0c;培养你的眼力 - 摄影构图&#xff0c;本文是整理自《美国纽约摄影学院 摄影教材》&#xff0c;第三单元 - 第9课 - 自然光&#xff0c;课后习题及解答。“ 1. 正面光产生无深浅反差的平面感觉。 理解这题&#xff0c;首先得明白什么是…

华为云Flexus+DeepSeek征文 | 华为云 ModelArts Studio 赋能高情商AI聊天助手:用技术构建有温度的智能对话体验

前言 华为云 ModelArts Studio 是基于 ModelArts 构建的一站式大模型即服务平台&#xff08;MaaS&#xff09;&#xff0c;可通过与开源 Agent 框架 Dify.AI 结合来开发对接 AI 聊天助手。 在打造 “高情商” 特性的过程中&#xff0c;华为云ModelArts Studio 的自定义提示词…

Spring Boot属性配置方式

一、Spring Boot属性配置方式。 在编写完成后端程序之前&#xff0c;可以通过yml配置文件键值对的方式修改配置环境&#xff0c;一旦打包完成&#xff0c;再次修改yml配置文件较为麻烦&#xff0c;此时&#xff0c;可以使用以下配置方式&#xff1a; 1.命令行参数方式 …

Webpack原理剖析与实现

1. 整体架构设计 Webpack 5 的整体架构设计包括以下几个核心模块: Compiler:负责整个编译过程,从读取配置、解析模块、生成依赖图,到输出最终的打包结果,主要文件是 lib/Compiler.js 。 Compilation:代表一次编译过程,包括所有模块、依赖关系和编译结果,主要文件是 li…

【Python使用】嘿马python运维开发全体系教程第2篇:日志管理,Linux概述【附代码文档】

教程总体简介&#xff1a;网络设定 学习目标 1、手动设定 2、DHCP自动获取 系统基本优化 一、永久关闭SELinux 1. 永久关闭 二、关闭防火墙 2. 临时启动关闭防火墙 三、设定运行级别为3&#xff08;命令行模式&#xff09; 四、修改ssh端口号 ssh服务 一、ssh介绍 二、客户端远…