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

[joint_state_publisher]: Waiting for robot_description to be published on the robot_description topic...

asked 2020-07-13 11:47:07 -0500

rydb gravatar image

updated 2020-07-19 11:07:19 -0500

Im using the below python launch file:

#!/usr/bin/env python3
import os
import sys

from ament_index_python.packages import get_package_share_directory


import rclpy
from rclpy.node import Node

from std_msgs.msg import String
import launch
import launch_ros.actions
from launch import LaunchDescription
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare

def generate_launch_description():
    # Load the URDF into a parameter
    bringup_dir = get_package_share_directory('urdfpublisher')
    urdf_path = os.path.join(bringup_dir, 'urdf', 'doggo.urdf')
    urdf = open(urdf_path).read()

    return launch.LaunchDescription([
        launch_ros.actions.Node(
            name='robot_state_publisher',
            package='robot_state_publisher',
            executable='robot_state_publisher',
            parameters=[{'robot_description': urdf}],
        ),
        launch_ros.actions.Node(
            name='joint_state_publisher',
            package='joint_state_publisher',
            executable='joint_state_publisher',
            parameters=[{'use_gui': True}],
        )
    ])



def main(argv=sys.argv[1:]):
    """Run lifecycle nodes via launch."""
    ld = generate_launch_description()
    ls = launch.LaunchService(argv=argv)
    ls.include_launch_description(ld)

    #launch robot_description topic
    node = rclpy.create_node('robot_description')
    publisher = node.create_publisher(generate_launch_description, 'robot_description', 10)

    #Fails when generating launch description with joint state publisher here
    publisher.publish(generate_launch_description)

    #publisher = node.create_publisher(String, 'sos')

    return ls.run()



if __name__ == '__main__':
    main()

to try and publish robot_description and joint_state_publisher with GUI enabled but I get the error "[joint_state_publisher]: Waiting for robot_description to be published on the robot_description topic..." thrown. When i remove joint_state_publisher, RVIZ2 is able to correctly pick up on robot_description meaning it should be getting published. The terminal logs also look nearly identical when joint_state_publisher is removed.

Launch file log with joint_state_publisher removed from "return launch.LaunchDescription" block:

[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [robot_state_publisher-1]: process started with pid [7135]
[robot_state_publisher-1] Parsing robot urdf xml string.
[robot_state_publisher-1] Link body_link had 0 children
[robot_state_publisher-1] [INFO] [1594658144.778155573] [robot_state_publisher]: got segment base_link
[robot_state_publisher-1] [INFO] [1594658144.778254258] [robot_state_publisher]: got segment body_link

Launch file log when joint_state_publisher isn't removed

[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [robot_state_publisher-1]: process started with pid [7078]
[INFO] [joint_state_publisher-2]: process started with pid [7080]
[robot_state_publisher-1] Parsing robot urdf xml string.
[robot_state_publisher-1] Link body_link had 0 children
[robot_state_publisher-1] [INFO] [1594657967.525358734] [robot_state_publisher]: got segment base_link
[robot_state_publisher-1] [INFO] [1594657967.525620189] [robot_state_publisher]: got segment body_link
[joint_state_publisher-2] [INFO] [1594657968.330320388] [joint_state_publisher]: Waiting for robot_description to be published on the robot_description topic...

Not sure why joint_state_publisher is being finicky and the joint_state_publisher GitHub page doesn't have any .py launch file examples.

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
2

answered 2020-07-22 12:47:01 -0500

rydb gravatar image

It seems I made a simple mistake, I couldnt find the joint state publisher for foxy for some reason but after following an example of how to use it here , it seems I wasn confusing ROS1 xml with ros2 python. I made a small revision to the joint_state_publisher node and it launches properly and the robot_state_publisher node listents to it without issue:

#!/usr/bin/env python3

import os
import sys

from ament_index_python.packages import get_package_share_directory

import launch
import launch_ros.actions


def generate_launch_description():
    # Load the URDF into a parameter
    bringup_dir = get_package_share_directory('urdfpublisher')
    urdf_path = os.path.join(bringup_dir, 'urdf', 'doggo.urdf')
    urdf = open(urdf_path).read()

    return launch.LaunchDescription([
        launch_ros.actions.Node(
            name='robot_state_publisher',
            package='robot_state_publisher',
            executable='robot_state_publisher',
            parameters=[{'robot_description': urdf}],
        ),
        launch_ros.actions.Node(
            package='joint_state_publisher',
            executable='joint_state_publisher',
            arguments=(urdf_path),
        ),
    ])


def main(argv=sys.argv[1:]):
    rospy.init_node('joint_state_publisher_gui')
    """Run lifecycle nodes via launch."""
    ld = generate_launch_description()
    ls = launch.LaunchService(argv=argv)
    ls.include_launch_description(ld)
    return ls.run()


if __name__ == '__main__':
    main()

[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [robot_state_publisher-1]: process started with pid [30524]
[INFO] [joint_state_publisher-2]: process started with pid [30526]
[robot_state_publisher-1] Parsing robot urdf xml string.
[robot_state_publisher-1] Link body_link had 0 children
[robot_state_publisher-1] [INFO] [1595439722.097627686] [robot_state_publisher]: got segment base_link
[robot_state_publisher-1] [INFO] [1595439722.097767815] [robot_state_publisher]: got segment body_link
edit flag offensive delete link more

Comments

1

I was having the same issue and you help me fix it! Just a quick note: to avoid an error, arguments must be provided in square brackets '[ ]' not in round ones '( )'. So the correct way to launch the node is:

launch_ros.actions.Node(
        package='joint_state_publisher',
        executable='joint_state_publisher',
        arguments=[urdf_path],
    ),

To use gui window you should launch 'joint_state_publisher_gui' node instead:

launch_ros.actions.Node(
        package='joint_state_publisher_gui',
        executable='joint_state_publisher_gui',
        arguments=[urdf_path],
    ),

Don't forget to have both packages installed (foxy in my case):

sudo apt install ros-foxy-joint-state-publisher
sudo apt install ros-foxy-joint-state-publisher-gui
dgarcialopez gravatar image dgarcialopez  ( 2021-07-24 07:44:05 -0500 )edit
0

answered 2020-07-20 05:47:00 -0500

hodnajit67 gravatar image

Joint_state_publisher helps you to simulate movement of nonfixed joints defined in your urdf model. If you run joint_state_publisher gui, you should see in popup window for example continous joints and you can move with them. If you run joint_state_publisher, it looks just like you described above.

If you want to be sure it works, you should see your robot in rviz2 with correctly placed links and joints. :)

Hope it helps

edit flag offensive delete link more

Comments

do you have or know an example of a joint state publisher topic with gui running correctly? The problem im having is i dont know how to implement it

rydb gravatar image rydb  ( 2020-07-20 15:12:59 -0500 )edit
1

I am using this one - https://github.com/ros/joint_state_pu... (you may use different branch according to your ros).

hodnajit67 gravatar image hodnajit67  ( 2020-07-22 02:02:58 -0500 )edit
hodnajit67 gravatar image hodnajit67  ( 2020-08-04 01:50:22 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2020-07-13 11:47:07 -0500

Seen: 3,213 times

Last updated: Jul 22 '20