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

Why isn't Gazebo publishing on the /odom topic on ROS2?

asked 2022-12-17 09:12:42 -0500

andi gravatar image

updated 2022-12-22 07:58:55 -0500

Mike Scheutzow gravatar image

Hey all! I'm having some problems with Gazebo. I'm using ROS2 foxy on UBUNTU 20.04.5 LTS with Gazebo installed via ros-foxy-gazebo. I made an URDF model on a differential drive robot, with a launch file to run gazebo and spawn the robot. Even though, when launching the file, it appears on the terminal that the diff_drive is advertising the /odom and publishing the tf between odom frame and base_link, i cannot find the frame odom in RVIZ2. Moreover, when echoing the /odom topic i have no results. Finally, in the view_frames the odom frame doesn't appear. I guess that i did the correct launch file with the diff_drive control plugin and the good parameters. Here below the files. Launch file:

import os

from ament_index_python.packages import get_package_share_directory


from launch import LaunchDescription
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource

from launch_ros.actions import Node


def generate_launch_description():

    # Include the robot_state_publisher launch file, provided by our own package. Force sim time to be enabled
    # !!! MAKE SURE YOU SET THE PACKAGE NAME CORRECTLY !!!

    package_name = 'package_test'  # <--- CHANGE ME

    rsp = IncludeLaunchDescription(
        PythonLaunchDescriptionSource([os.path.join(
            get_package_share_directory(
                package_name), 'launch', 'rsp.launch.py'
        )]), launch_arguments={'use_sim_time': 'true'}.items()
    )
# Include the Gazebo launch file, provided by the gazebo_ros package
gazebo = IncludeLaunchDescription(
    PythonLaunchDescriptionSource([os.path.join(
        get_package_share_directory('gazebo_ros'), 'launch', 'gazebo.launch.py')]),
)

# Run the spawner node from the gazebo_ros package. The entity name doesn't really matter if you only have a single robot.
spawn_entity = Node(package='gazebo_ros', executable='spawn_entity.py',
                    arguments=['-topic', 'robot_description',
                               '-entity', 'my_bot'],
                    output='screen')

# Launch them all!
return LaunchDescription([
    rsp,
    gazebo,
    spawn_entity,
])

Gazebo plugin:

<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro"  name="robot">

   <gazebo>
        <plugin name="diff_drive" filename="libgazebo_ros_diff_drive.so">
            <!-- Wheel info-->
            <left_joint>left_wheel_joint</left_joint>
            <right_joint>right_wheel_joint</right_joint>
            <wheel_separation>0.35</wheel_separation>
            <wheel_diameter>0.1</wheel_diameter>

            <!-- Limits-->
            <max_wheel_torque>200</max_wheel_torque>
            <max_wheel_acceleration>10.0</max_wheel_acceleration>

            <!-- Output-->
            <odometry_frame>odom</odometry_frame>
            <robot_base_frame>base_link</robot_base_frame>

            <publish_odom>true</publish_odom> 
            <publish_odom_tf>true</publish_odom_tf> 
            <publish_wheel_tf>true</publish_wheel_tf> 

        </plugin>


     </gazebo>

</robot>

URDF file:

<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" >

    <xacro:include filename="inertial_macros.xacro"/>

    <material name="white">
        <color rgba="1 1 1 1" />
    </material>

    <material name="orange">
        <color rgba="1 0.3 0.1 1"/>
    </material>

    <material name="blue">
        <color rgba="0.2 0.2 1 1"/>
    </material>

    <material name="black">
        <color rgba="0 0 0 1"/>
    </material>

    <!-- BASE LINK -->

    <link name="base_link">

    </link>


    <!-- CHASSIS LINK -->

    <joint name="chassis_joint" type="fixed">
        <parent link="base_link"/>
        <child link="chassis"/>
        <origin xyz="-0.1 0 0"/>
    </joint>

    <link name="chassis">
        <visual>
            <origin xyz="0.15 0 0.075"/>
            <geometry>
                <box size="0.3 0.3 0.15"/>
            </geometry>
            <material name="white"/>
        </visual>
        <collision>
            <origin xyz="0.15 0 0.075"/>
            <geometry>
                <box size="0.3 0.3 0.15"/>
            </geometry>
        < ...
(more)
edit retag flag offensive close merge delete

Comments

In ros1, you need <transmission> tags in your urdf when simulating with ros_control. I don't know if this has changed for ros2, but it seems unlikely.

Mike Scheutzow gravatar image Mike Scheutzow  ( 2022-12-22 07:54:11 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2023-01-11 03:09:47 -0500

rodrigo55 gravatar image

I would first check if your plugin file is being called correctly by the main xacro, unless you have something like an SDF model where you can define everything. Do other sensor plugins work?

Comparing it to a working example like ROBOTIS TurtleBot3, it seems like the tags <command_topic> and <odometry_topic> are needed in the plugin:

https://github.com/ROBOTIS-GIT/turtle...

If you want to see a video on gazebo plugins and ROS2, I made a video based on your question: https://youtu.be/JJDebiniDBw

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2022-12-17 09:12:42 -0500

Seen: 651 times

Last updated: Jan 11 '23