鱼香ROS社区
    • 版块
    • 最新
    • 未解决
    • 已解决
    • 群组
    • 注册
    • 登录
    紧急通知:禁止一切关于政治&VPN翻墙等话题,发现相关帖子会立马删除封号
    提问前必看的发帖注意事项: 社区问答规则(小鱼个人)更新 | 高质量帖子发布指南

    Warning: Invalid frame ID "back_wheel" passed to canTransform argument source_frame - frame does not exist

    已定时 已固定 已锁定 已移动 已解决
    综合问题
    urdf warning
    2
    3
    1.5k
    正在加载更多帖子
    • 从旧到新
    • 从新到旧
    • 最多赞同
    回复
    • 在新帖中回复
    登录后回复
    此主题已被删除。只有拥有主题管理权限的用户可以查看。
    • 2716585362
      ℡﹏smˋ背靠背の承诺
      最后由 小鱼 编辑

      urdf文件

      <?xml version="1.0" ?>
      <!-- =================================================================================== -->
      <!-- |    This document was autogenerated by xacro from test03_my_car.xacro            | -->
      <!-- |    EDITING THIS FILE BY HAND IS NOT RECOMMENDED                                 | -->
      <!-- =================================================================================== -->
      <!-- 组合小车底盘与摄像头与雷达 -->
      <robot name="my_car">
        <!-- 圆柱惯性矩阵 -->
        <!-- 立方体惯性矩阵 -->
        <!-- 宏:黑色设置 -->
        <material name="black">
          <color rgba="0.0 0.0 0.0 1.0"/>
        </material>
        <!-- 质量  -->
        <!-- 底盘 -->
        <link name="base_footprint">
          <visual>
            <geometry>
              <sphere radius="0.001"/>
            </geometry>
          </visual>
        </link>
        <link name="base_link">
          <visual>
            <geometry>
              <cylinder length="0.08" radius="0.1"/>
            </geometry>
            <origin rpy="0 0 0" xyz="0 0 0"/>
            <material name="yellow">
              <color rgba="0.5 0.3 0.0 0.5"/>
            </material>
          </visual>
          <collision>
            <geometry>
              <cylinder length="0.08" radius="0.1"/>
            </geometry>
            <origin rpy="0 0 0" xyz="0 0 0"/>
          </collision>
          <inertial>
            <mass value="0.5"/>
            <inertia ixx="0.001516666666666667" ixy="0" ixz="0" iyy="0.001516666666666667" iyz="0" izz="0.0025000000000000005"/>
          </inertial>
        </link>
        <joint name="base_link2base_footprint" type="fixed">
          <parent link="base_footprint"/>
          <child link="base_link"/>
          <origin xyz="0 0 0.055"/>
        </joint>
        <gazebo reference="base_link">
          <material>Gazebo/Yellow</material>
        </gazebo>
        <!-- 质量  -->
        <link name="left_wheel">
          <visual>
            <geometry>
              <cylinder length="0.015" radius="0.0325"/>
            </geometry>
            <origin rpy="1.5707963 0.0 0.0" xyz="0.0 0.0 0.0"/>
            <material name="black"/>
          </visual>
          <collision>
            <geometry>
              <cylinder length="0.015" radius="0.0325"/>
            </geometry>
            <origin rpy="1.5707963 0.0 0.0" xyz="0.0 0.0 0.0"/>
          </collision>
          <inertial>
            <mass value="0.05"/>
            <inertia ixx="1.4140625000000002e-05" ixy="0" ixz="0" iyy="1.4140625000000002e-05" iyz="0" izz="2.6406250000000005e-05"/>
          </inertial>
        </link>
        <joint name="left_wheel2base_link" type="continuous">
          <parent link="base_link"/>
          <child link="left_wheel"/>
          <origin xyz="0 0.1 -0.0225"/>
          <axis xyz="0 1 0"/>
        </joint>
        <gazebo reference="left_wheel">
          <material>Gazebo/Red</material>
        </gazebo>
        <link name="right_wheel">
          <visual>
            <geometry>
              <cylinder length="0.015" radius="0.0325"/>
            </geometry>
            <origin rpy="1.5707963 0.0 0.0" xyz="0.0 0.0 0.0"/>
            <material name="black"/>
          </visual>
          <collision>
            <geometry>
              <cylinder length="0.015" radius="0.0325"/>
            </geometry>
            <origin rpy="1.5707963 0.0 0.0" xyz="0.0 0.0 0.0"/>
          </collision>
          <inertial>
            <mass value="0.05"/>
            <inertia ixx="1.4140625000000002e-05" ixy="0" ixz="0" iyy="1.4140625000000002e-05" iyz="0" izz="2.6406250000000005e-05"/>
          </inertial>
        </link>
        <joint name="right_wheel2base_link" type="continuous">
          <parent link="base_link"/>
          <child link="right_wheel"/>
          <origin xyz="0 -0.1 -0.0225"/>
          <axis xyz="0 1 0"/>
        </joint>
        <gazebo reference="right_wheel">
          <material>Gazebo/Red</material>
        </gazebo>
        <!-- 质量  -->
        <link name="front_wheel">
          <visual>
            <geometry>
              <sphere radius="0.0075"/>
            </geometry>
            <origin rpy="0 0 0" xyz="0 0 0"/>
            <material name="black"/>
          </visual>
          <collision>
            <geometry>
              <sphere radius="0.0075"/>
            </geometry>
            <origin rpy="0 0 0" xyz="0 0 0"/>
          </collision>
          <inertial>
            <mass value="0.03"/>
            <inertia ixx="6.75e-07" ixy="0" ixz="0" iyy="6.75e-07" iyz="0" izz="6.75e-07"/>
          </inertial>
        </link>
        <joint name="front_wheel2base_link" type="continuous">
          <parent link="base_link"/>
          <child link="front_wheel"/>
          <origin xyz="0.0925 0 -0.0475"/>
          <axis xyz="1 1 1"/>
        </joint>
        <gazebo reference="front_wheel">
          <material>Gazebo/Red</material>
        </gazebo>
        <link name="back_wheel">
          <visual>
            <geometry>
              <sphere radius="0.0075"/>
            </geometry>
            <origin rpy="0 0 0" xyz="0 0 0"/>
            <material name="black"/>
          </visual>
          <collision>
            <geometry>
              <sphere radius="0.0075"/>
            </geometry>
            <origin rpy="0 0 0" xyz="0 0 0"/>
          </collision>
          <inertial>
            <mass value="0.03"/>
            <inertia ixx="6.75e-07" ixy="0" ixz="0" iyy="6.75e-07" iyz="0" izz="6.75e-07"/>
          </inertial>
        </link>
        <joint name="back_wheel2base_link" type="continuous">
          <parent link="base_link"/>
          <child link="back_wheel"/>
          <origin xyz="-0.0925 0 -0.0475"/>
          <axis xyz="1 1 1"/>
        </joint>
        <gazebo reference="back_wheel">
          <material>Gazebo/Red</material>
        </gazebo>
        <!-- 摄像头安装的z坐标:底盘高度 / 2 + 摄像头高度 / 2  -->
        <!-- 摄像头质量 -->
        <!-- 摄像头关节以及link -->
        <link name="camera">
          <visual>
            <geometry>
              <box size="0.01 0.025 0.025"/>
            </geometry>
            <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
            <material name="black"/>
          </visual>
          <collision>
            <geometry>
              <box size="0.01 0.025 0.025"/>
            </geometry>
            <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
          </collision>
          <inertial>
            <mass value="0.01"/>
            <inertia ixx="6.041666666666668e-07" ixy="0" ixz="0" iyy="6.041666666666668e-07" iyz="0" izz="1.041666666666667e-06"/>
          </inertial>
        </link>
        <joint name="camera2base_link" type="fixed">
          <parent link="base_link"/>
          <child link="camera"/>
          <origin xyz="0.08 0.0 0.052500000000000005"/>
        </joint>
        <gazebo reference="camera">
          <material>Gazebo/Blue</material>
        </gazebo>
        <!-- 支架安装的z坐标:底盘高度 / 2 + 支架高度 / 2  -->
        <!-- 支架质量 -->
        <link name="support">
          <visual>
            <geometry>
              <cylinder length="0.15" radius="0.01"/>
            </geometry>
            <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
            <material name="red">
              <color rgba="0.8 0.2 0.0 0.8"/>
            </material>
          </visual>
          <collision>
            <geometry>
              <cylinder length="0.15" radius="0.01"/>
            </geometry>
            <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
          </collision>
          <inertial>
            <mass value="0.02"/>
            <inertia ixx="3.8e-05" ixy="0" ixz="0" iyy="3.8e-05" iyz="0" izz="1.0000000000000002e-06"/>
          </inertial>
        </link>
        <joint name="support2base_link" type="fixed">
          <parent link="base_link"/>
          <child link="support"/>
          <origin xyz="0.0 0.0 0.11499999999999999"/>
        </joint>
        <gazebo reference="support">
          <material>Gazebo/White</material>
        </gazebo>
        <!-- 雷达安装的z坐标:支架高度 / 2 + 雷达高度 / 2  -->
        <!-- 雷达质量 -->
        <!-- 雷达关节以及link -->
        <link name="laser">
          <visual>
            <geometry>
              <cylinder length="0.05" radius="0.03"/>
            </geometry>
            <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
            <material name="black"/>
          </visual>
          <collision>
            <geometry>
              <cylinder length="0.05" radius="0.03"/>
            </geometry>
            <origin rpy="0.0 0.0 0.0" xyz="0.0 0.0 0.0"/>
          </collision>
          <inertial>
            <mass value="0.1"/>
            <inertia ixx="4.333333333333333e-05" ixy="0" ixz="0" iyy="4.333333333333333e-05" iyz="0" izz="4.4999999999999996e-05"/>
          </inertial>
        </link>
        <joint name="laser2support" type="fixed">
          <parent link="support"/>
          <child link="laser"/>
          <origin xyz="0.0 0.0 0.1"/>
        </joint>
        <gazebo reference="laser">
          <material>Gazebo/Black</material>
        </gazebo>
        <!-- 控制器 -->
        <gazebo>
          <plugin name='diff_drive' filename='libgazebo_ros_diff_drive.so'>
                <ros>
                  <namespace>/</namespace>
                  <remapping>cmd_vel:=cmd_vel</remapping>
                  <remapping>odom:=odom</remapping>
                </ros>
                <update_rate>30</update_rate>
                <left_joint>left_wheel2base_link</left_joint>
                <right_joint>right_wheel2base_link</right_joint>
                <!-- kinematics -->
                <wheel_separation>0.2</wheel_separation>
                <wheel_diameter>0.065</wheel_diameter>
                <!-- limits -->
                <max_wheel_torque>20</max_wheel_torque>
                <max_wheel_acceleration>1.0</max_wheel_acceleration>
                <!-- output -->
                <publish_odom>true</publish_odom>
                <publish_odom_tf>true</publish_odom_tf>
                <publish_wheel_tf>false</publish_wheel_tf>
                <odometry_frame>odom</odometry_frame>
                <robot_base_frame>base_footprint</robot_base_frame>
            </plugin>
            <plugin name="fishbot_joint_state" filename="libgazebo_ros_joint_state_publisher.so">
                <ros>
                  <remapping>~/out:=joint_states</remapping>
                </ros>
                <update_rate>30</update_rate>
                <joint_name>left_wheel2base_link</joint_name>
                <joint_name>right_wheel2base_link</joint_name>
            </plugin>    
        </gazebo>
      </robot>
      
      

      launch代码

      import os
      from launch import LaunchDescription
      from launch.actions import ExecuteProcess
      from launch.substitutions import LaunchConfiguration
      from launch_ros.actions import Node
      from launch_ros.substitutions import FindPackageShare
      
      
      def generate_launch_description():
          package_name = 'fishbot_description'
          urdf_name = "test04.urdf"
          rviz_name = "demo01.rviz"
          robot_name_in_model = 'fishbot'
      
          ld = LaunchDescription()
          pkg_share = FindPackageShare(package=package_name).find(package_name) 
          urdf_model_path = os.path.join(pkg_share, f'urdf/{urdf_name}')
          rviz_path_ = os.path.join(pkg_share, f'config/{rviz_name}')
          gazebo_world_path = os.path.join(pkg_share, 'world/box_house.world')
      
      
           # Start Gazebo server
          start_gazebo_cmd = ExecuteProcess(
              cmd=['gazebo', '--verbose', '-s', 'libgazebo_ros_factory.so',gazebo_world_path],
              output='screen')
      
           # Launch the robot
          spawn_entity_cmd = Node(
              package='gazebo_ros', 
              executable='spawn_entity.py',
              arguments=['-entity', robot_name_in_model,  '-file', urdf_model_path ], output='screen')
      
      
          # 添加机器人状态发布节点
          robot_state_publisher_node = Node(
              package='robot_state_publisher',
              executable='robot_state_publisher',
              name='robot_state_publisher',
              arguments=[urdf_model_path]
              )
      
          # 可选:用于控制关节运动的节点
          joint_state_publisher_gui_node = Node(
              package='joint_state_publisher_gui',
              executable='joint_state_publisher_gui',
              name='joint_state_publisher_gui',
              arguments=[urdf_model_path]
              )
      
          rviz2_node = Node(
              package='rviz2',
              executable='rviz2',
              name='rviz2',
              output='screen',
              arguments=['-d', rviz_path_]
              # arguments=['-d', rviz_path]
              )
      
          ld.add_action(start_gazebo_cmd)
          ld.add_action(spawn_entity_cmd)
          ld.add_action(robot_state_publisher_node)
          # ld.add_action(joint_state_publisher_gui_node)
          ld.add_action(rviz2_node)
      
          return ld
      
      运行launch文件后会出现警告是怎么回事呢
      [rviz2-4]          at line 133 in /tmp/binarydeb/ros-foxy-tf2-0.13.13/src/buffer_core.cpp
      [rviz2-4] Warning: Invalid frame ID "back_wheel" passed to canTransform argument source_frame - frame does not exist
      [rviz2-4]          at line 133 in /tmp/binarydeb/ros-foxy-tf2-0.13.13/src/buffer_core.cpp
      [rviz2-4] Warning: Invalid frame ID "front_wheel" passed to canTransform argument source_frame - frame does not exist
      [rviz2-4]          at line 133 in /tmp/binarydeb/ros-foxy-tf2-0.13.13/src/buffer_core.cpp
      [rviz2-4] Warning: Invalid frame ID "back_wheel" passed to canTransform argument source_frame - frame does not exist
      [rviz2-4]          at line 133 in /tmp/binarydeb/ros-foxy-tf2-0.13.13/src/buffer_core.cpp
      [rviz2-4] Warning: Invalid frame ID "front_wheel" passed to canTransform argument source_frame - frame does not exist
      [rviz2-4]          at line 133 in /tmp/binarydeb/ros-foxy-tf2-0.13.13/src/buffer_core.cpp
      [rviz2-4] Warning: Invalid frame ID "back_wheel" passed to canTransform argument source_frame - frame does not exist
      [rviz2-4]          at line 133 in /tmp/binarydeb/ros-foxy-tf2-0.13.13/src/buffer_core.cpp
      [rviz2-4] Warning: Invalid frame ID "front_wheel" passed to canTransform argument source_frame - frame does not exist
      [rviz2-4]          at line 133 in /tmp/binarydeb/ros-foxy-tf2-0.13.13/src/buffer_core.cpp
      [rviz2-4] Warning: Invalid frame ID "back_wheel" passed to canTransform argument source_frame - frame does not exist
      [rviz2-4]          at line 133 in /tmp/binarydeb/ros-foxy-tf2-0.13.13/src/buffer_core.cpp
      [rviz2-4] Warning: Invalid frame ID "front_wheel" passed to canTransform argument source_frame - frame does not exist
      [rviz2-4]          at line 133 in /tmp/binarydeb/ros-foxy-tf2-0.13.13/src/buffer_core.cpp
      [rviz2-4] Warning: Invalid frame ID "back_wheel" passed to canTransform argument source_frame - frame does not exist
      [rviz2-4]          at line 133 in /tmp/binarydeb/ros-foxy-tf2-0.13.13/src/buffer_core.cpp
      [rviz2-4] Warning: Invalid frame ID "front_wheel" passed to canTransform argument source_frame - frame does not exist
      [rviz2-4]          at line 133 in /tmp/binarydeb/ros-foxy-tf2-0.13.13/src/buffer_core.cpp
      [rviz2-4] Warning: Invalid frame ID "back_wheel" passed to canTransform argument source_frame - frame does not exist
      [rviz2-4]          at line 133 in /tmp/binarydeb/ros-foxy-tf2-0.13.13/src/buffer_core.cpp
      [rviz2-4] Warning: Invalid frame ID "front_wheel" passed to canTransform argument source_frame - frame does not exist
      [rviz2-4]          at line 133 in /tmp/binarydeb/ros-foxy-tf2-0.13.13/src/buffer_core.cpp
      [rviz2-4] Warning: Invalid frame ID "back_wheel" passed to canTransform argument source_frame - frame does not exist
      [rviz2-4]          at line 133 in /tmp/binarydeb/ros-foxy-tf2-0.13.13/src/buffer_core.cpp
      [rviz2-4] Warning: Invalid frame ID "front_wheel" passed to canTransform argument source_frame - frame does not exist
      [rviz2-4]          at line 133 in /tmp/binarydeb/ros-foxy-tf2-0.13.13/src/buffer_core.cpp
      [rviz2-4] Warning: Invalid frame ID "back_wheel" passed to canTransform argument source_frame - frame does not exist
      [rviz2-4]          at line 133 in /tmp/binarydeb/ros-foxy-tf2-0.13.13/src/buffer_core.cpp
      [rviz2-4] Warning: Invalid frame ID "front_wheel" passed to canTransform argument source_frame - frame does not exist
      [rviz2-4]          at line 133 in /tmp/binarydeb/ros-foxy-tf2-0.13.13/src/buffer_core.cpp
      [rviz2-4] Warning: Invalid frame ID "back_wheel" passed to canTransform argument source_frame - frame does not exist
      [rviz2-4]          at line 133 in /tmp/binarydeb/ros-foxy-tf2-0.13.13/src/buffer_core.cpp
      [rviz2-4] Warning: Invalid frame ID "front_wheel" passed to canTransform argument source_frame - frame does not exist
      [rviz2-4]          at line 133 in /tmp/binarydeb/ros-foxy-tf2-0.13.13/src/buffer_core.cpp
      [rviz2-4] Warning: Invalid frame ID "back_wheel" passed to canTransform argument source_frame - frame does not exist
      [rviz2-4]          at line 133 in /tmp/binarydeb/ros-foxy-tf2-0.13.13/src/buffer_core.cpp
      [rviz2-4] Warning: Invalid frame ID "front_wheel" passed to canTransform argument source_frame - frame does not exist
      [rviz2-4]          at line 133 in /tmp/binarydeb/ros-foxy-tf2-0.13.13/src/buffer_core.cpp
      [rviz2-4] Warning: Invalid frame ID "back_wheel" passed to canTransform argument source_frame - frame does not exist
      [rviz2-4]          at line 133 in /tmp/binarydeb/ros-foxy-tf2-0.13.13/src/buffer_core.cpp
      [rviz2-4] Warning: Invalid frame ID "front_wheel" passed to canTransform argument source_frame - frame does not exist
      [rviz2-4]          at line 133 in /tmp/binarydeb/ros-foxy-tf2-0.13.13/src/buffer_core.cpp
      [rviz2-4] Warning: Invalid frame ID "back_wheel" passed to canTransform argument source_frame - frame does not exist
      [rviz2-4]          at line 133 in /tmp/binarydeb/ros-foxy-tf2-0.13.13/src/buffer_core.cpp
      [rviz2-4] Warning: Invalid frame ID "front_wheel" passed to canTransform argument source_frame - frame does not exist
      [rviz2-4]          at line 133 in /tmp/binarydeb/ros-foxy-tf2-0.13.13/src/buffer_core.cpp
      
      小鱼小 1 条回复 最后回复 回复 引用 0
      • 小鱼小
        小鱼 技术大佬 @271658536
        最后由 小鱼 编辑

        @271658536 在 Warning: Invalid frame ID "back_wheel" passed to canTransform argument source_frame - frame does not exist 中说:

          <plugin name="fishbot_joint_state" filename="libgazebo_ros_joint_state_publisher.so">
              <ros>
                <remapping>~/out:=joint_states</remapping>
              </ros>
              <update_rate>30</update_rate>
              <joint_name>left_wheel2base_link</joint_name>
              <joint_name>right_wheel2base_link</joint_name>
          </plugin>   
        

        在这里加入下front_wheel back_wheel

        新书配套视频:https://www.bilibili.com/video/BV1GW42197Ck/

        2716585362 1 条回复 最后回复 回复 引用 0
        • 2716585362
          ℡﹏smˋ背靠背の承诺 @小鱼
          最后由 编辑

          @小鱼 感谢小鱼大佬,问题得到解决

          1 条回复 最后回复 回复 引用 0
          • 2716585362 271658536 将这个主题标记为已解决,在
          • 第一个帖子
            最后一个帖子
          皖ICP备16016415号-7
          Powered by NodeBB | 鱼香ROS