0
$\begingroup$

I'm simulating a robot with 4 omnidirectional wheels and I'm using the planar move plugin in the gazebo to simulate the behavior of the omnidirectional wheels.

To simulate the wheels I was using continuous joints however with this plugin in rviz2 and with the fixed frame in odom, the wheels do not move with the robot. Although if I'm using a fixed joint and controlling the robot with teleop_twist_keyboard the wheels move together with the robot.

Is this a plugin problem or am I missing something to declare?

Follows URDF code to create the robot.

robot_core:

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

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

    <material name="white">
        <color rgba="1 1 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>
    <material name="red">
        <color rgba="1 0 0 1"/>
    </material>

    <!--BASE LINK-->
    <link name="base_link">
    </link>

    <!--CHASSI-->
    <joint name="chassi_joint" type="fixed">
        <parent link="base_link"/>
        <child link="chassi_link"/>
        <origin xyz="0 0 0"/> <!--VIRADO PARA X-->
        <!--<origin xyz="0 0 0" rpy="0 0 ${pi/2}"/> VIRADO PARA Y-->
    </joint>

    <link name="chassi_link">
        <visual>
            <origin xyz="0 0 0.085"/>
            <geometry>
                <cylinder radius="0.275" length="0.17"/>
            </geometry>
            <material name="white"/>
        </visual>
        <collision>
            <origin xyz="0 0 0.085"/>
            <geometry>
                <cylinder radius="0.275" length="0.17"/>
            </geometry>
        </collision>
        <xacro:inertial_cylinder mass="0.1" length="0.17" radius="0.275">
            <origin xyz="0 0 0.085" rpy="0 0 0"/>
        </xacro:inertial_cylinder>
    </link>

    <gazebo reference="chassi_link">
        <material>Gazebo/White</material>
    </gazebo>

    <!--BODY-->
    <joint name="body_joint" type="fixed">
        <parent link="chassi_link"/>
        <child link="body_link"/>
        <origin xyz="-0.1 0 0.18" rpy="0 0 0"/>
    </joint>

    <link name="body_link">
        <visual>
            <origin xyz="0 0 0.55" rpy="0 0 ${pi/2}"/>
        <geometry>
            <box size="0.2 0.05 1.1"/>
        </geometry>
        <material name="white"/>
    </visual>
    <collision>
        <origin xyz="0 0 0.55" rpy="0 0 ${pi/2}"/>
            <geometry>
                <box size="0.2 0.05 1.1"/>
            </geometry>
        </collision>
        <xacro:inertial_box mass="0.1" x="0.2" y="0.05" z="1.1">
            <origin xyz="0 0 0.55" rpy="0 0 0"/>
        </xacro:inertial_box>
    </link>

    <gazebo reference="body_link">
        <material>Gazebo/White</material>
    </gazebo>

    <!--WHEELS-->

    <!--LEFT FRONT-->
    <joint name="left_front_joint" type="fixed">
        <parent link="chassi_link"/>
        <child link="left_front_link"/>
        <origin xyz="0.2 0.2 0" rpy="-${pi/2} 0 -${pi/4}"/>
        <!--<axis xyz="0 0 1"/>-->
    </joint>

    <link name="left_front_link">
        <visual>
            <geometry>
                <cylinder radius="0.1" length="0.04"/>
            </geometry>
            <material name="blue"/>
        </visual>
        <collision>
            <geometry>
                <cylinder radius="0.1" length="0.04"/>
            </geometry>
        </collision>
        <xacro:inertial_cylinder mass="0.1" length="0.04" radius="0.1">
            <origin xyz="0 0 0" rpy="0 0 0"/>
        </xacro:inertial_cylinder>
    </link>

    <gazebo reference="left_front_link">
        <material>Gazebo/Blue</material>
        <mu1 value="0.001"/>
        <mu2 value="0.001"/>
    </gazebo>

    <!--LEFT BACK-->
    <joint name="left_back_joint" type="fixed">
        <parent link="chassi_link"/>
        <child link="left_back_link"/>
        <origin xyz="-0.2 0.2 0" rpy="0 -${pi/2} -${pi/4}"/>
        <!--<axis xyz="0 0 1"/>-->
    </joint>

    <link name="left_back_link">
        <visual>
            <geometry>
                <cylinder radius="0.1" length="0.04"/>
            </geometry>
            <material name="black"/>
        </visual>
        <collision>
            <geometry>
                <cylinder radius="0.1" length="0.04"/>
            </geometry>
        </collision>
        <xacro:inertial_cylinder mass="0.1" length="0.04" radius="0.1">
            <origin xyz="0 0 0" rpy="0 0 0"/>
        </xacro:inertial_cylinder>
    </link>

    <gazebo reference="left_back_link">
        <material>Gazebo/Black</material>
        <mu1 value="0.001"/>
        <mu2 value="0.001"/>
    </gazebo>

    <!--RIGHT FRONT-->
    <joint name="right_front_joint" type="fixed">
        <parent link="chassi_link"/>
        <child link="right_front_link"/>
        <origin xyz="0.2 -0.2 0" rpy="0 ${pi/2} -${pi/4}"/>
        <!--<axis xyz="0 0 -1"/>-->
    </joint>

    <link name="right_front_link">
        <visual>
            <geometry>
                <cylinder radius="0.1" length="0.04"/>
            </geometry>
            <material name="blue"/>
        </visual>
        <collision>
            <geometry>
                <cylinder radius="0.1" length="0.04"/>
            </geometry>
        </collision>
        <xacro:inertial_cylinder mass="0.1" length="0.04" radius="0.1">
            <origin xyz="0 0 0" rpy="0 0 0"/>
        </xacro:inertial_cylinder>
    </link>

    <gazebo reference="right_front_link">
        <material>Gazebo/Blue</material>
        <mu1 value="0.001"/>
        <mu2 value="0.001"/>
    </gazebo>

    <!--RIGHT BACK-->
    <joint name="right_back_joint" type="fixed">
        <parent link="chassi_link"/>
        <child link="right_back_link"/>
        <origin xyz="-0.2 -0.2 0" rpy="${pi/2} 0 -${pi/4}"/>
        <!--<axis xyz="0 0 -1"/>-->
    </joint>

    <link name="right_back_link">
        <visual>
            <geometry>
                <cylinder radius="0.1" length="0.04"/>
            </geometry>
            <material name="black"/>
        </visual>
        <collision>
            <geometry>
                <cylinder radius="0.1" length="0.04"/>
            </geometry>
        </collision>
        <xacro:inertial_cylinder mass="0.1" length="0.04" radius="0.1">
            <origin xyz="0 0 0" rpy="0 0 0"/>
        </xacro:inertial_cylinder>
    </link>

    <gazebo reference="right_back_link">
        <material>Gazebo/Black</material>
        <mu1 value="0.001"/>
        <mu2 value="0.001"/>
    </gazebo>
    
    <xacro:omni_steering/>

</robot>

gazebo_control:

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

    <xacro:macro name="omni_steering" params="">
        <gazebo>

             <plugin name="omni_steering" filename="libgazebo_ros_planar_move.so">
                <commandTopic>cmd_vel</commandTopic>
                <odometry_rate>50.0</odometry_rate>                
                <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>
  </xacro:macro>

</robot>

robot_xacro:

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

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

</robot>

rsp.launch.py:

import os

from ament_index_python.packages import get_package_share_directory

from launch import LaunchDescription from launch.substitutions import LaunchConfiguration from launch.actions import DeclareLaunchArgument from launch_ros.actions import Node

import xacro

def generate_launch_description():

# Check if we're told to use sim time
use_sim_time = LaunchConfiguration('use_sim_time')

# Process the URDF file
pkg_path = os.path.join(get_package_share_directory('charmie_bot'))
xacro_file = os.path.join(pkg_path,'description','robot.urdf.xacro')
robot_description_config = xacro.process_file(xacro_file)
    
# Create a robot_state_publisher node
params = {'robot_description': robot_description_config.toxml(), 'use_sim_time': use_sim_time}
node_robot_state_publisher = Node(
    package='robot_state_publisher',
    executable='robot_state_publisher',
    output='screen',
    parameters=[params]
)

# Launch!
return LaunchDescription([
    DeclareLaunchArgument(
        'use_sim_time',
        default_value='false',
        description='Use sim time if true'),
    node_robot_state_publisher
])

launch_sim.launch.py:

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():

package_name='charmie_bot' #<--- 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
])
$\endgroup$

1 Answer 1

1
$\begingroup$

This usually happens when you do not set the use_sim_time parameter as True in the simulation.
Attached below is the launch file I used to run rviz2 with your robot with the set parameters: ​

#! /usr/bin/env python3
"""Spawn Robot in RViz2."""
​
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.substitutions import LaunchConfiguration, Command
from launch.actions import DeclareLaunchArgument
from launch_ros.actions import Node
​
​
def generate_launch_description():
    """Launch Function."""
    pkg_dir = get_package_share_directory('your_ros2_pkg')
    rviz_config = os.path.join(pkg_dir, 'config', 'rviz', 'urdf.rviz')
​
    return LaunchDescription([
        # Launch Arguments
        DeclareLaunchArgument("rviz_config",
                              default_value=rviz_config,
                              description="RViz Config"),
​
        # Nodes
        Node(
            package='joint_state_publisher',
            executable='joint_state_publisher',
            name='joint_state_publisher',
            output='screen',
            parameters=[{'use_sim_time': True}],
        ),
​
        Node(
            package='robot_state_publisher',
            executable='robot_state_publisher',
            parameters=[
                {'use_sim_time': True},
                {'robot_description': Command(
                    ['xacro ', os.path.join(pkg_dir, 'urdf/robot.xacro')])}
                ]
        ),
​
        Node(
            package='rviz2',
            executable='rviz2',
            output='screen',
            arguments=['-d', LaunchConfiguration("rviz_config")],
        ),
    ])
  • Below is the run of the planar move plugin with continuous joints enabled: ​
  • Additionally, your plugin definition has incorrect XML header tags. Refer to the official gazebo_ros_pkgs migration doc to get the updated plugin definition.

Edit:

It seems that you have not included joint_state_publisher in the rsp.launch.py script.
Modify the launch file to add the node:

node_joint_state_publisher = Node(
    package='joint_state_publisher',
    executable='joint_state_publisher',
    name='joint_state_publisher',
    output='screen',
    parameters=[{'use_sim_time': use_sim_time}],
)
$\endgroup$
3
  • $\begingroup$ thanks for your help. iust edit my post i and attached my 2 launch files in there i use_sim_time as true and i have the same issue what i need to change in my launch files thanks $\endgroup$
    – Rui Silva
    Commented May 25, 2023 at 9:38
  • $\begingroup$ Refer to the edited answer to match the launch files you've sent. $\endgroup$ Commented May 26, 2023 at 7:24
  • $\begingroup$ The missing joint state publisher in the edited answer sounds correct. $\endgroup$
    – Tully
    Commented May 27, 2023 at 12:25

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.

Not the answer you're looking for? Browse other questions tagged or ask your own question.