ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Localization issue: Waiting for Transform odom -> base_link

asked 2023-04-04 15:47:01 -0500

Vini71 gravatar image

Hi I am doing this nav2 tutorial https://navigation.ros.org/setup_guid... However instead of a differential drive robot, I am using a car-like robot (Ackermann kinematics). It also published odometry message as well as imu. These are my topics being published:

 /accel/filtered
/clock
/demo/cmd_vel
/demo/distance
/demo/imu
/demo/odom
/diagnostics
/joint_states
/odometry/filtered
/parameter_events
/performance_metrics
/robot_description
/rosout
/set_pose
/tf
/tf_static

My issue is that when I run the command:

ros2 run tf2_ros tf2_echo odom base_link

I do not receive the transform data as I should (as below):

At time 8.842000000
 - Translation: [0.003, -0.000, 0.127]
 - Rotation: in Quaternion [-0.000, 0.092, 0.003, 0.996]
At time 9.842000000
 - Translation: [0.002, -0.000, 0.127]
 - Rotation: in Quaternion [-0.000, 0.092, 0.003, 0.996

Instead, I get this error message when launching just rviz:

 [INFO] [1680639826.322243365] [tf2_echo]: Waiting for transform odom ->  base_link: Invalid frame ID "odom" passed to canTransform argument target_frame - frame does not exist
[INFO] [1680639826.322243365] [tf2_echo]: Waiting for transform odom ->  base_link: Invalid frame ID "odom" passed to canTransform argument target_frame - frame does not exist

If i include to launch Gazebo on my launch file I get this error message:

[INFO] [1680639826.322243365] [tf2_echo]: Waiting for transform odom ->  base_link: Invalid frame ID "odom" passed to canTransform argument target_frame - frame does not exist
Warning: TF_OLD_DATA ignoring data from the past for frame front_right_wheel_link at time 30.685000 according to authority Authority undetectable
Possible reasons are listed at http://wiki.ros.org/tf/Errors%20explained
         at line 355 in /tmp/binarydeb/ros-galactic-tf2-0.17.5/src/buffer_core.cpp
Warning: TF_OLD_DATA ignoring data from the past for frame front_left_wheel_link at time 30.685000 according to authority Authority undetectable
Possible reasons are listed at http://wiki.ros.org/tf/Errors%20explained
         at line 355 in /tmp/binarydeb/ros-galactic-tf2-0.17.5/src/buffer_core.cpp
Warning: TF_OLD_DATA ignoring data from the past for frame rear_second_right_wheel_link at time 30.685000 according to authority Authority undetectable
Possible reasons are listed at http://wiki.ros.org/tf/Errors%20explained
         at line 355 in /tmp/binarydeb/ros-galactic-tf2-0.17.5/src/buffer_core.cpp
Warning: TF_OLD_DATA ignoring data from the past for frame rear_second_left_wheel_link at time 30.685000 according to authority Authority undetectable
Possible reasons are listed at http://wiki.ros.org/tf/Errors%20explained
         at line 355 in /tmp/binarydeb/ros-galactic-tf2-0.17.5/src/buffer_core.cpp
Warning: TF_OLD_DATA ignoring data from the past for frame front_right_axle_link at time 30.685000 according to authority Authority undetectable

Does it seem that my TF2 publisher is delayed? I don't understand why because I am using a very powerful computer (NUC). Some expert suggestions?

My robot xacro file: urdf My launch file: dispaly.launch.py localization configuration file: ekf.yaml

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2023-04-10 14:25:47 -0500

Vini71 gravatar image

For some reason, if I don't remove the node which launches the guide of joint_state_publisher. This node will interfere in the transformation of Odom to base_link and raise the error above. Then just comment out this block of code, which allowed me to get the transform properly.

My launch file below:

import launch
from launch.substitutions import Command, LaunchConfiguration
import launch_ros
import os

def generate_launch_description():
    pkg_share = launch_ros.substitutions.FindPackageShare(package='sam_bot_description').find('sam_bot_description')
    default_model_path = os.path.join(pkg_share, 'src/description/aroc_truck_description.urdf')
    default_rviz_config_path = os.path.join(pkg_share, 'rviz/urdf_config.rviz')
    world_path=os.path.join(pkg_share, 'world/my_world.sdf')

    robot_state_publisher_node = launch_ros.actions.Node(
        package='robot_state_publisher',
        executable='robot_state_publisher',
        parameters=[{'robot_description': Command(['xacro ', LaunchConfiguration('model')])}]
    )
    joint_state_publisher_node = launch_ros.actions.Node(
        package='joint_state_publisher',
        executable='joint_state_publisher',
        name='joint_state_publisher',
        condition=launch.conditions.UnlessCondition(LaunchConfiguration('gui'))
    )
    # joint_state_publisher_gui_node = launch_ros.actions.Node(
    #     package='joint_state_publisher_gui',
    #     executable='joint_state_publisher_gui',
    #     name='joint_state_publisher_gui',
    #     condition=launch.conditions.IfCondition(LaunchConfiguration('gui'))
    # )
    rviz_node = launch_ros.actions.Node(
        package='rviz2',
        executable='rviz2',
        name='rviz2',
        output='screen',
        arguments=['-d', LaunchConfiguration('rvizconfig')],
    )

    spawn_entity = launch_ros.actions.Node(
        package='gazebo_ros',
        executable='spawn_entity.py',
        arguments=['-entity', 'sam_bot', '-topic', 'robot_description'],
        output='screen'
    )

    robot_localization_node = launch_ros.actions.Node(
       package='robot_localization',
       executable='ekf_node',
       name='ekf_filter_node',
       output='screen',
       parameters=[os.path.join(pkg_share, 'config/ekf.yaml'), {'use_sim_time': LaunchConfiguration('use_sim_time')}]
)

    return launch.LaunchDescription([
        launch.actions.DeclareLaunchArgument(name='gui', default_value='True',
                                            description='Flag to enable joint_state_publisher_gui'),
        launch.actions.DeclareLaunchArgument(name='model', default_value=default_model_path,
                                            description='Absolute path to robot urdf file'),
        launch.actions.DeclareLaunchArgument(name='rvizconfig', default_value=default_rviz_config_path,
                                            description='Absolute path to rviz config file'),
        launch.actions.DeclareLaunchArgument(name='use_sim_time', default_value='True',
                                            description='Flag to enable use_sim_time'),
        launch.actions.ExecuteProcess(cmd=['gazebo', '--verbose', '-s', 'libgazebo_ros_init.so', '-s', 'libgazebo_ros_factory.so'], output='screen'),
        joint_state_publisher_node,
        #joint_state_publisher_gui_node,
        robot_state_publisher_node,
        spawn_entity,
        robot_localization_node,
        rviz_node
    ])

After this got the expected result:

$ ros2 run tf2_ros tf2_echo odom base_link

**

[INFO] [1681154384.590858888] [tf2_echo]: Waiting for transform odom ->  base_link: Invalid frame ID "odom" passed to canTransform argument target_frame - frame does not exist
At time 2.1000000
- Translation: [-0.000, -0.022, 0.900]
- Rotation: in Quaternion [0.000, 0.000, 0.001, 1.000]
At time 3.1000000
- Translation: [-0.001, -0.023, 0.900]
- Rotation: in Quaternion [0.000, 0.000, 0.001, 1.000]
At time 4.1000000
- Translation: [-0.001, -0.023, 0.900]
- Rotation: in Quaternion [0.000, 0.000, 0.001, 1.000]
^C[INFO] [1681154388.348508517] [rclcpp]: signal_handler(signal_value=2)

**

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2023-04-04 15:47:01 -0500

Seen: 197 times

Last updated: Apr 10 '23