Gazebo仿真 ros control中的节点启动问题
-
四驱四转小车,gazebo启动成功:
但是在运行以下代码时出错:- ros2 control load_controller position_controller
- ros2 control set_controller_state position_controller active
- ros2 control set_controller_state position_controller inactive
出错截图:
gazebo进程报错:
YAML文件截图:
URDF文件:<?xml version="1.0"?> <robot name="SLDASM6"> <link name="base_footprint"/> <joint name="base_joint" type="fixed"> <parent link="base_footprint"/> <child link="base_link"/> <origin rpy="0 0 0" xyz="0 0 0"/> </joint> <link name="base_link"> <inertial> <origin xyz="0 2.81892564846231E-18 -0.01" rpy="0 0 0" /> <mass value="0.454477345778312" /> <inertia ixx="0.000871431296911177" ixy="-1.28282275253518E-09" ixz="-8.22671320090087E-21" iyy="0.000871738130550077" iyz="-1.30062780621123E-21" izz="0.0017128709377427" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="/home/longqianjiang/gazebo_demo/src/myrobot/meshes/base_link.STL" /> </geometry> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="/home/longqianjiang/gazebo_demo/src/myrobot/meshes/base_link.STL" /> </geometry> </collision> </link> <link name="LINK1"> <inertial> <origin xyz="0 -1.38777878078145E-17 -0.0358503670123729" rpy="0 0 0" /> <mass value="0.00733856168867493" /> <inertia ixx="4.05757150334916E-06" ixy="-4.63221143029695E-23" ixz="2.76505770768833E-23" iyy="3.99722848663285E-06" iyz="4.18774943094673E-22" izz="2.67495324757519E-07" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="/home/longqianjiang/gazebo_demo/src/myrobot/meshes/LINK1.STL" /> </geometry> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="/home/longqianjiang/gazebo_demo/src/myrobot/meshes/LINK1.STL" /> </geometry> </collision> </link> <joint name="J1" type="continuous"> <origin xyz="0.0654792997866397 0.0666132205566422 0" rpy="0 0 0" /> <parent link="base_link" /> <child link="LINK1" /> <axis xyz="0 0 1" /> <hardwareInterface>Position</hardwareInterface> </joint> <link name="LINK11"> <inertial> <origin xyz="0 -1.38777878078145E-17 2.77555756156289E-17" rpy="0 0 0" /> <mass value="0.0327888025255167" /> <inertia ixx="8.01891151764667E-06" ixy="-1.38966342908909E-22" ixz="5.38638611724067E-22" iyy="1.52508917746809E-05" iyz="2.6315261058982E-22" izz="8.01891151764667E-06" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="/home/longqianjiang/gazebo_demo/src/myrobot/meshes/LINK11.STL" /> </geometry> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="/home/longqianjiang/gazebo_demo/src/myrobot/meshes/LINK11.STL" /> </geometry> </collision> </link> <joint name="J11" type="continuous"> <origin xyz="0 0 -0.07" rpy="0 0 0" /> <parent link="LINK1" /> <child link="LINK11" /> <axis xyz="0 1 0" /> <hardwareInterface>Velocity</hardwareInterface> </joint> <link name="LINK2"> <inertial> <origin xyz="-6.93889390390723E-18 0 -0.0358503670123729" rpy="0 0 0" /> <mass value="0.00733856168867492" /> <inertia ixx="4.05757150334916E-06" ixy="2.31610571514848E-23" ixz="-3.83931492667846E-22" iyy="3.99722848663285E-06" iyz="-5.47440727449521E-22" izz="2.67495324757519E-07" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="/home/longqianjiang/gazebo_demo/src/myrobot/meshes/LINK2.STL" /> </geometry> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="/home/longqianjiang/gazebo_demo/src/myrobot/meshes/LINK2.STL" /> </geometry> </collision> </link> <joint name="J2" type="continuous"> <origin xyz="0.065479 -0.065785 0" rpy="0 0 0" /> <parent link="base_link" /> <child link="LINK2" /> <axis xyz="0 0 1" /> <hardwareInterface>Position</hardwareInterface> </joint> <link name="LINK22"> <inertial> <origin xyz="0 0 2.77555756156289E-17" rpy="0 0 0" /> <mass value="0.0327888025255167" /> <inertia ixx="8.01891151764668E-06" ixy="1.23911655760444E-21" ixz="1.87271335385636E-23" iyy="1.5250891774681E-05" iyz="9.5134033420699E-22" izz="8.01891151764668E-06" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="/home/longqianjiang/gazebo_demo/src/myrobot/meshes/LINK22.STL" /> </geometry> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="/home/longqianjiang/gazebo_demo/src/myrobot/meshes/LINK22.STL" /> </geometry> </collision> </link> <joint name="J22" type="continuous"> <origin xyz="0 0 -0.0700000000000011" rpy="0 0 0" /> <parent link="LINK2" /> <child link="LINK22" /> <axis xyz="0 1 0" /> <hardwareInterface>Velocity</hardwareInterface> </joint> <link name="LINK3"> <inertial> <origin xyz="1.38777878078145E-17 0 -0.0358503670123729" rpy="0 0 0" /> <mass value="0.00733856168867492" /> <inertia ixx="4.05757150334916E-06" ixy="-2.11758236813575E-22" ixz="-3.43745650941657E-22" iyy="3.99722848663285E-06" iyz="-4.01213179299295E-23" izz="2.67495324757519E-07" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="/home/longqianjiang/gazebo_demo/src/myrobot/meshes/LINK3.STL" /> </geometry> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="/home/longqianjiang/gazebo_demo/src/myrobot/meshes/LINK3.STL" /> </geometry> </collision> </link> <joint name="J3" type="continuous"> <origin xyz="-0.066308 0.066613 0" rpy="0 0 0" /> <parent link="base_link" /> <child link="LINK3" /> <axis xyz="0 0 1" /> <hardwareInterface>Position</hardwareInterface> </joint> <link name="LINK33"> <inertial> <origin xyz="0 -2.77555756156289E-17 0" rpy="0 0 0" /> <mass value="0.0327888025255167" /> <inertia ixx="8.01891151764667E-06" ixy="1.32348898008484E-23" ixz="1.20319233745711E-22" iyy="1.52508917746809E-05" iyz="1.48231251644303E-22" izz="8.01891151764667E-06" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="/home/longqianjiang/gazebo_demo/src/myrobot/meshes/LINK33.STL" /> </geometry> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="/home/longqianjiang/gazebo_demo/src/myrobot/meshes/LINK33.STL" /> </geometry> </collision> </link> <joint name="J33" type="continuous"> <origin xyz="0 0 -0.07" rpy="0 0 0" /> <parent link="LINK3" /> <child link="LINK33" /> <axis xyz="0 1 0" /> <hardwareInterface>Velocity</hardwareInterface> </joint> <link name="LINK4"> <inertial> <origin xyz="0 0 -0.0358503670123729" rpy="0 0 0" /> <mass value="0.00733856168867491" /> <inertia ixx="4.05757150334916E-06" ixy="-1.55159629369121E-44" ixz="1.32642618950926E-22" iyy="3.99722848663285E-06" iyz="-1.35845611653203E-22" izz="2.67495324757518E-07" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="/home/longqianjiang/gazebo_demo/src/myrobot/meshes/LINK4.STL" /> </geometry> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="/home/longqianjiang/gazebo_demo/src/myrobot/meshes/LINK4.STL" /> </geometry> </collision> </link> <joint name="J4" type="continuous"> <origin xyz="-0.0663076865851465 -0.0657848337581353 0" rpy="0 0 0" /> <parent link="base_link" /> <child link="LINK4" /> <axis xyz="0 0 1" /> <hardwareInterface>Position</hardwareInterface> </joint> <link name="LINK44"> <inertial> <origin xyz="1.38777878078145E-17 0 0" rpy="0 0 0" /> <mass value="0.0327888025255167" /> <inertia ixx="8.01891151764667E-06" ixy="1.05879118406788E-22" ixz="1.72429389430485E-21" iyy="1.52508917746809E-05" iyz="-1.73567112915338E-22" izz="8.01891151764667E-06" /> </inertial> <visual> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="/home/longqianjiang/gazebo_demo/src/myrobot/meshes/LINK44.STL" /> </geometry> </visual> <collision> <origin xyz="0 0 0" rpy="0 0 0" /> <geometry> <mesh filename="/home/longqianjiang/gazebo_demo/src/myrobot/meshes/LINK44.STL" /> </geometry> </collision> </link> <joint name="J44" type="continuous"> <origin xyz="0 0 -0.0700000000000004" rpy="0 0 0" /> <parent link="LINK4" /> <child link="LINK44" /> <axis xyz="0 1 0" /> <hardwareInterface>Velocity</hardwareInterface> </joint> <gazebo reference="base_link"> <material>Gazebo/Red</material> </gazebo> <gazebo reference="LINK1"> <material>Gazebo/Red</material> </gazebo> <gazebo reference="LINK2"> <material>Gazebo/Green</material> </gazebo> <gazebo reference="LINK3"> <material>Gazebo/Blue</material> </gazebo> <gazebo> <plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control"> <parameters>/home/longqianjiang/gazebo_demo/src/myrobot/config/controller.yaml</parameters> </plugin> </gazebo> <ros2_control name="GazeboSystem" type="system"> <hardware> <plugin>gazebo_ros2_control/GazeboSystem</plugin> </hardware> <joint name="J1"> <command_interface name="position"> <param name="min">-3.140000001</param> <param name="max">3.140000001</param> <param name="initial_value">0.00000001</param> </command_interface> <state_interface name="position"/> <state_interface name="velocity"/> <param name="initial_value">0.00000001</param> </joint> <joint name="J11"> <command_interface name="velocity"> <param name="min">-3.140000001</param> <param name="max">3.140000001</param> </command_interface> <state_interface name="velocity"/> <param name="initial_value">0.00000001</param> <state_interface name="position"> <param name="initial_value">0.00000001</param> </state_interface> </joint> <joint name="J2"> <command_interface name="position"> <param name="min">-3.140000001</param> <param name="max">3.140000001</param> <param name="initial_value">0.00000001</param> </command_interface> <state_interface name="position"/> <state_interface name="velocity"/> <param name="initial_value">0.00000001</param> </joint> <joint name="J22"> <command_interface name="velocity"> <param name="min">-3.140000001</param> <param name="max">3.140000001</param> </command_interface> <state_interface name="velocity"/> <param name="initial_value">0.00000001</param> <state_interface name="position"> <param name="initial_value">0.00000001</param> </state_interface> </joint> <joint name="J3"> <command_interface name="position"> <param name="min">-3.140000001</param> <param name="max">3.140000001</param> <param name="initial_value">0.00000001</param> </command_interface> <state_interface name="position"/> <state_interface name="velocity"/> <param name="initial_value">0.00000001</param> </joint> <joint name="J33"> <command_interface name="velocity"> <param name="min">-3.140000001</param> <param name="max">3.140000001</param> </command_interface> <state_interface name="velocity"/> <param name="initial_value">0.00000001</param> <state_interface name="position"> <param name="initial_value">0.00000001</param> </state_interface> </joint> <joint name="J4"> <command_interface name="position"> <param name="min">-3.140000001</param> <param name="max">3.140000001</param> <param name="initial_value">0.00000001</param> </command_interface> <state_interface name="position"/> <state_interface name="velocity"/> <param name="initial_value">0.00000001</param> </joint> <joint name="J44"> <command_interface name="velocity"> <param name="min">-3.140000001</param> <param name="max">3.140000001</param> </command_interface> <state_interface name="velocity"/> <param name="initial_value">0.00000001</param> <state_interface name="position"> <param name="initial_value">0.00000001</param> </state_interface> </joint> </ros2_control> </robot>
-
上面说我的'joints' parameter was empty ,可是我的controllers.yaml就放在\wsl.localhost\Ubuntu-22.04\home\longqianjiang\gazebo_demo\src\myrobot\config下面,URDF上写了绝对路径,应该是可以读到的,怎么会为空呢
-
自己解决了,是yaml的问题,改成如下格式即可,
controller_manager:
ros__parameters:
update_rate: 100
joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster
position_controller:
type: position_controllers/JointGroupPositionControllerposition_controller:
ros__parameters:
joints:
- J1韭菜会自己长出来的是吧?
-
@956635683 emmmm?
-
@小鱼 鱼,gazebo有没有四驱四转的插件啊,自己写太痛苦了,网上比较多的是两驱差速,四驱看到一个差速的,四驱全向没找到
-
@956635683 这个大概率没有的,需要自己整