I keep getting this error
[rviz2-2] Warning: Invalid frame ID "left_wheel" passed to canTransform argument source_frame - frame does not exist
[rviz2-2] at line 156 in /tmp/binarydeb/ros-galactic-tf2-0.17.2/src/buffer_core.cpp
[rviz2-2] Warning: Invalid frame ID "right_wheel" passed to canTransform argument source_frame - frame does not exist
[rviz2-2] at line 156 in /tmp/binarydeb/ros-galactic-tf2-0.17.2/src/buffer_core.cpp
[rviz2-2] Warning: Invalid frame ID "back_pitch_link" passed to canTransform argument source_frame - frame does not exist
[rviz2-2] at line 156 in /tmp/binarydeb/ros-galactic-tf2-0.17.2/src/buffer_core.cpp
[rviz2-2] Warning: Invalid frame ID "back_roll_link" passed to canTransform argument source_frame - frame does not exist
[rviz2-2] at line 156 in /tmp/binarydeb/ros-galactic-tf2-0.17.2/src/buffer_core.cpp
[rviz2-2] Warning: Invalid frame ID "back_yaw_link" passed to canTransform argument source_frame - frame does not exist
[rviz2-2] at line 156 in /tmp/binarydeb/ros-galactic-tf2-0.17.2/src/buffer_core.cpp
[rviz2-2] Warning: Invalid frame ID "front_pitch_link" passed to canTransform argument source_frame - frame does not exist
[rviz2-2] at line 156 in /tmp/binarydeb/ros-galactic-tf2-0.17.2/src/buffer_core.cpp
[rviz2-2] Warning: Invalid frame ID "front_roll_link" passed to canTransform argument source_frame - frame does not exist
[rviz2-2] at line 156 in /tmp/binarydeb/ros-galactic-tf2-0.17.2/src/buffer_core.cpp
[rviz2-2] Warning: Invalid frame ID "front_yaw_link" passed to canTransform argument source_frame - frame does not exist
[rviz2-2] at line 156 in /tmp/binarydeb/ros-galactic-tf2-0.17.2/src/buffer_core.cpp
[rviz2-2] Warning: Invalid frame ID "left_wheel" passed to canTransform argument source_frame - frame does not exist
[rviz2-2] at line 156 in /tmp/binarydeb/ros-galactic-tf2-0.17.2/src/buffer_core.cpp
[rviz2-2] Warning: Invalid frame ID "right_wheel" passed to canTransform argument source_frame - frame does not exist
[rviz2-2] at line 156 in /tmp/binarydeb/ros-galactic-tf2-0.17.2/src/buffer_core.cpp
[rviz2-2] Warning: Invalid frame ID "back_pitch_link" passed to canTransform argument source_frame - frame does not exist
[rviz2-2] at line 156 in /tmp/binarydeb/ros-galactic-tf2-0.17.2/src/buffer_core.cpp
[rviz2-2] Warning: Invalid frame ID "back_roll_link" passed to canTransform argument source_frame - frame does not exist
[rviz2-2] at line 156 in /tmp/binarydeb/ros-galactic-tf2-0.17.2/src/buffer_core.cpp
[rviz2-2] Warning: Invalid frame ID "back_yaw_link" passed to canTransform argument source_frame - frame does not exist
this is my box_bot_geometric.urdf
<?xml version="1.0"?>
<robot name="box_bot">
<material name="red">
<color rgba="1.0 0.0 0.0 1"/>
</material>
<material name="green_light">
<color rgba="0.0 1.0 0.0 1"/>
</material>
<material name="green_dark">
<color rgba="0.0 0.5 0.0 1"/>
</material>
<material name="blue">
<color rgba="0.0 0.0 1.0 1"/>
</material>
<material name="black">
<color rgba="0.0 0.0 0.0 1"/>
</material>
<material name="white">
<color rgba="1.0 1.0 1.0 1"/>
</material>
<material name="box_bot_blue">
<color rgba="0.088656 0.428691 0.491021 1"/>
</material>
<link name="base_link">
</link>
<!-- Body -->
<link name="chassis">
<visual>
<geometry>
<box size="0.1 0.1 0.1"/>
</geometry>
<material name="box_bot_blue"/>
</visual>
</link>
<joint name="base_link_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0" />
<parent link="base_link" />
<child link="chassis" />
</joint>
<!-- Wheel Left -->
<link name="left_wheel">
<visual>
<origin rpy="0 1.5707 1.5707" xyz="0 0 0"/>
<geometry>
<cylinder length="0.001" radius="0.035"/>
</geometry>
<material name="black"/>
</visual>
</link>
<joint name="joint_left_wheel" type="continuous">
<origin rpy="0 0 0" xyz="0 0.05 -0.025"/>
<parent link="chassis"/>
<child link="left_wheel"/>
<axis rpy="0 0 0" xyz="0 1 0"/>
<limit effort="10000" velocity="1000"/>
<joint_properties damping="1.0" friction="1.0"/>
</joint>
<!-- Wheel Right -->
<link name="right_wheel">
<visual>
<origin rpy="0 1.5707 1.5707" xyz="0 0 0"/>
<geometry>
<cylinder length="0.001" radius="0.035"/>
</geometry>
<material name="white"/>
</visual>
</link>
<joint name="joint_right_wheel" type="continuous">
<origin rpy="0 0 0" xyz="0 -0.05 -0.025"/>
<parent link="chassis"/>
<child link="right_wheel"/>
<axis rpy="0 0 0" xyz="0 1 0"/>
<limit effort="10000" velocity="1000"/>
<joint_properties damping="1.0" friction="1.0"/>
</joint>
<!-- Caster Wheel Front -->
<link name="front_yaw_link">
<visual>
<origin rpy="0 1.5707 1.5707" xyz="0 0 0"/>
<geometry>
<cylinder length="0.005" radius="0.010"/>
</geometry>
<material name="blue"/>
</visual>
</link>
<joint name="front_yaw_joint" type="continuous">
<origin rpy="0 0 0" xyz="0.04 0 -0.05" />
<parent link="chassis" />
<child link="front_yaw_link" />
<axis xyz="0 0 1" />
<limit effort="1000.0" velocity="100.0" />
<dynamics damping="0.0" friction="0.1"/>
</joint>
<link name="front_roll_link">
<visual>
<origin rpy="0 1.5707 1.5707" xyz="0 0 0"/>
<geometry>
<cylinder length="0.005" radius="0.010"/>
</geometry>
<material name="red"/>
</visual>
</link>
<joint name="front_roll_joint" type="continuous">
<origin rpy="0 0 0" xyz="0 0 0" />
<parent link="front_yaw_link" />
<child link="front_roll_link" />
<axis xyz="1 0 0" />
<limit effort="1000.0" velocity="100.0" />
<dynamics damping="0.0" friction="0.1"/>
</joint>
<link name="front_pitch_link">
<visual>
<origin rpy="0 1.5707 1.5707" xyz="0 0 0"/>
<geometry>
<sphere radius="0.010"/>
</geometry>
<material name="green_dark"/>
</visual>
</link>
<joint name="front_pitch_joint" type="continuous">
<origin rpy="0 0 0" xyz="0 0 0" />
<parent link="front_roll_link" />
<child link="front_pitch_link" />
<axis xyz="0 1 0" />
<limit effort="1000.0" velocity="100.0" />
<dynamics damping="0.0" friction="0.1"/>
</joint>
<!-- Caster Wheel Back -->
<link name="back_yaw_link">
<visual>
<origin rpy="0 1.5707 1.5707" xyz="0 0 0"/>
<geometry>
<cylinder length="0.005" radius="0.010"/>
</geometry>
<material name="blue"/>
</visual>
</link>
<joint name="back_yaw_joint" type="continuous">
<origin rpy="0 0 0" xyz="-0.04 0 -0.05" />
<parent link="chassis" />
<child link="back_yaw_link" />
<axis xyz="0 0 1" />
<limit effort="1000.0" velocity="100.0" />
<dynamics damping="0.0" friction="0.1"/>
</joint>
<link name="back_roll_link">
<visual>
<origin rpy="0 1.5707 1.5707" xyz="0 0 0"/>
<geometry>
<cylinder length="0.005" radius="0.010"/>
</geometry>
<material name="red"/>
</visual>
</link>
<joint name="back_roll_joint" type="continuous">
<origin rpy="0 0 0" xyz="0 0 0" />
<parent link="back_yaw_link" />
<child link="back_roll_link" />
<axis xyz="1 0 0" />
<limit effort="1000.0" velocity="100.0" />
<dynamics damping="0.0" friction="0.1"/>
</joint>
<link name="back_pitch_link">
<visual>
<origin rpy="0 1.5707 1.5707" xyz="0 0 0"/>
<geometry>
<sphere radius="0.010"/>
</geometry>
<material name="green_light"/>
</visual>
</link>
<joint name="back_pitch_joint" type="continuous">
<origin rpy="0 0 0" xyz="0 0 0" />
<parent link="back_roll_link" />
<child link="back_pitch_link" />
<axis xyz="0 1 0" />
<limit effort="1000.0" velocity="100.0" />
<dynamics damping="0.0" friction="0.1"/>
</joint>
</robot>
my launch file
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.substitutions import Command
from launch_ros.actions import Node
# this is the function launch system will look for
def generate_launch_description():
####### DATA INPUT ##########
urdf_file = 'box_bot_geometric.urdf'
#xacro_file = "box_bot.xacro"
package_description = "my_box_bot_description"
####### DATA INPUT END ##########
print("Fetching URDF ==>")
robot_desc_path = os.path.join(get_package_share_directory(package_description), "urdf", urdf_file)
# Robot State Publisher
robot_state_publisher_node = Node(
package='robot_state_publisher',
executable='robot_state_publisher',
name='robot_state_publisher_node',
emulate_tty=True,
parameters=[{'use_sim_time': True, 'robot_description': Command(['xacro ', robot_desc_path])}],
output="screen"
)
# RVIZ Configuration
rviz_config_dir = os.path.join(get_package_share_directory(package_description), 'rviz', 'urdf_vis.rviz')
rviz_node = Node(
package='rviz2',
executable='rviz2',
output='screen',
name='rviz_node',
parameters=[{'use_sim_time': True}],
arguments=['-d', rviz_config_dir])
# create and return launch description object
return LaunchDescription(
[
robot_state_publisher_node,
rviz_node
]
)
I even checked rqt_tf_tree and all I could see was base_link being connected to chassis. I am unable to understand why other components are not showing up. I have checked parent and child names but still couldn’t solve this error.