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

a plugin for individual wheel on a 4 wheel robot in gazebo? Ros2 (foxy)

asked 2021-08-10 16:09:04 -0500

kak13 gravatar image

updated 2021-08-24 15:09:46 -0500

Hi everyone,

I have a question. So, is there any single plugin that works with individual wheel on robot with 4 wheels?

I'm using Gazebo11 and Foxy (ros2).

As I'm aware that libgazebo_ros_diff_drive controls 2 wheels and libgazebo_ros_ackermann_drive controls 4 wheels. I wanted to have a plugin where I'm able to control a single wheel or run with all wheels individual. Do you know the name of the plugin? Any tutorial too?

Thank you so much for your time!

Update 2

Here is my current launch file:

#!/usr/bin/env python3


from launch.substitutions import Command, LaunchConfiguration
from ament_index_python.packages import get_package_share_directory
from launch.substitutions import Command, FindExecutable, PathJoinSubstitution
from launch_ros.substitutions import FindPackageShare
from launch import LaunchDescription
from launch_ros.actions import Node
from launch import LaunchDescription, LaunchContext
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
from launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution
from launch.conditions import IfCondition, UnlessCondition
from launch.launch_description_sources import PythonLaunchDescriptionSource
import launch_ros
import os
import sys
import launch_ros.actions
import xacro
import launch


def generate_launch_description():
    pkg_path = FindPackageShare("my_robot_description")

    use_sim = LaunchConfiguration("use_sim")
    use_fake_hardware = LaunchConfiguration("use_fake_hardware")
    fake_sensor_commands = LaunchConfiguration("fake_sensor_commands")

    xacro_path = PathJoinSubstitution([pkg_path, "urdf", "my_robot.urdf"])
    assert os.path.exists(xacro_path.perform(LaunchContext())), (
    "The xacro file doesn't exist (" + str(xacro_path.perform(LaunchContext())) + ")"
    )



    robot_description_content = Command(
    [
        PathJoinSubstitution([FindExecutable(name="xacro")]),
        " ",
        PathJoinSubstitution(
            [
                PathJoinSubstitution([FindExecutable(name="xacro")]),
                " ",
                xacro_path,
                " ",
                "use_sim:=",
                use_sim,
                " ",
                "use_fake_hardware:=",
                use_fake_hardware,
                " ",
                "fake_sensor_commands:=",
                fake_sensor_commands,

                FindPackageShare("my_robot_description"),
                "src/description",
                "my_robot.urdf",
            ]
        ),
    ]
    )

    robot_description = {"robot_description": robot_description_content}

    controller_config_path = PathJoinSubstitution(
    [
        pkg_path,
        "config",
        "gazebo_ros_control_params.yaml",
    ]
    )
    assert os.path.exists(controller_config_path.perform(LaunchContext())), (
    "The controller config doesn't exist ("
    + str(controller_config_path.perform(LaunchContext()))
    + ")"
    )

    robot_description = {"robot_description": robot_description_content}
    rviz_config_file = PathJoinSubstitution(
    [FindPackageShare("my_robot_description"), "rviz", "urdf_config.rviz"]
    )

    rviz_node = Node(
    package="rviz2",
    executable="rviz2",
    name="rviz2",
    output="log",
    arguments=["-d", rviz_config_file],
    )
    robot_state_pub_node = Node(
    package="robot_state_publisher",
    executable="robot_state_publisher",
    output="both",
    parameters=[robot_description],
    )
    spawn_entity = launch_ros.actions.Node(
    package='gazebo_ros',
    executable='spawn_entity.py',
    arguments=['-entity', 'my_robot', '-topic', 'robot_description'],
    output='screen'
    )

    return launch.LaunchDescription([
    #
    # Launch Arguments
    #
    DeclareLaunchArgument(
        "use_sim",
        default_value="false",
        description="Use simulation (Gazebo) clock if true",
    ),
    DeclareLaunchArgument(
        "use_fake_hardware",
        default_value="true",
        description="Start robot with fake hardware mirroring command to its states.",
    ),
    DeclareLaunchArgument(
        "fake_sensor_commands",
        default_value="false",
        description="Enable fake command interfaces for sensors used for simple simulations. \
                Used only if 'use_fake_hardware' parameter is true.",
    ),
    Node(
        package="controller_manager",
        executable="ros2_control_node",
        parameters=[robot_description, controller_config_path],
        output={
            "stdout": "screen",
            "stderr": "screen",
        },
        condition=UnlessCondition(use_sim),
    ),
    Node(
        package="robot_state_publisher",
        executable="robot_state_publisher",
        output="both",
        parameters=[robot_description, {"use_sim_time": use_sim}],
    ),
    Node(
        package="controller_manager",
        executable="spawner.py",
        arguments=[
            "joint_state_broadcaster",
            "--controller-manager",
            "/controller_manager",
        ],
    ),
    Node(
        package="controller_manager",
        executable="spawner.py",
        arguments=["wheel_velocity_controller", "-c", "/controller_manager"],
    ),
    launch.actions.ExecuteProcess(cmd=['gazebo', '--verbose', '-s', 'libgazebo_ros_factory.so'], output='screen'),
    launch.actions.ExecuteProcess(
        name='fake_joint_calibration',
        cmd=['ros2', 'topic', 'pub', '/joint_states', 'sensor_msgs/msg/JointState', '"{data True}"'],
        output='screen',
        shell='True'
    ),

    robot_state_pub_node,
    rviz_node,
    spawn_entity,
    ])
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2021-08-24 04:47:07 -0500

Darkproduct gravatar image

updated 2021-08-24 18:04:18 -0500

I'm not really an expert on this and I myself struggled the last two weeks with ROS2, Gazebo and ROS2_Control, but I think you should be able to use ROS2_Control for that.

Here some useful links:

You have to add a ros2_control tag to your URDF file. (ref). Mine looks like this:

  <!-- ROS Control for the rims -->
  <ros2_control name="cassiopeia_rim_control" type="system">
    <xacro:if value="$(arg use_sim)">
      <hardware>
        <plugin>gazebo_ros2_control/GazeboSystem</plugin>
      </hardware>
    </xacro:if>
    <xacro:unless value="$(arg use_sim)">
      <hardware>
        <xacro:if value="$(arg use_fake_hardware)">
          <plugin>fake_components/GenericSystem</plugin>
          <param name="fake_sensor_commands">$(arg fake_sensor_commands)</param>
          <param name="state_following_offset">0.0</param>
        </xacro:if>
        <xacro:unless value="$(arg use_fake_hardware)">
          <!-- TODO: If we want this feature, we have to write an
                     hardware controller plugin in C++ for ROS2 Control.
            -->
        </xacro:unless>
      </hardware>
    </xacro:unless>

    <joint name="a_rim_joint">
      <command_interface name="velocity">
        <param name="min">-1</param>
        <param name="max">1</param>
      </command_interface>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
    </joint>
    <joint name="b_rim_joint">
      <command_interface name="velocity">
        <param name="min">-1</param>
        <param name="max">1</param>
      </command_interface>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
    </joint>
    <joint name="c_rim_joint">
      <command_interface name="velocity">
        <param name="min">-1</param>
        <param name="max">1</param>
      </command_interface>
      <state_interface name="position"/>
      <state_interface name="velocity"/>
    </joint>
  </ros2_control>

  <gazebo>
    <plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">
      <parameters>$(find pkg_name)/config/controllers.yaml</parameters>
    </plugin>
  </gazebo>

It is worth noting that, if you want to use ROS2 Control with gazebo, you have to use one ros2_control tag with type system for all joints. Additionally, the xacro:if in the beginning is if you want to use the same model in Gazebo and on the real robot. If you are only interested in Gazebo, just evaluate use_sim to true.

Then you'll also need the specified controllers.yaml. Here is mine:

controller_manager:
  ros__parameters:
    update_rate: 100  # Hz

    joint_state_broadcaster:
      type: joint_state_broadcaster/JointStateBroadcaster

    wheel_velocity_controller:
      type: velocity_controllers/JointGroupVelocityController


wheel_velocity_controller:
  ros__parameters:
    joints:
      - a_rim_joint
      - b_rim_joint
      - c_rim_joint

    command_interfaces:
      - velocity

    state_interfaces:
      - position
      - velocity

Here we have one controller for all three joints, that can be controlled with topic: /wheel_velocity_controller/commands of type: Type: std_msgs/msg/Float64MultiArray. If you want different topics for each joint, just define more controllers in the yaml file.

Update 1: Here is my launch file:

from launch import LaunchDescription, LaunchContext
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
from launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution
from launch.conditions import IfCondition, UnlessCondition
from launch.launch_description_sources import PythonLaunchDescriptionSource

from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare

import os


def generate_launch_description():
    pkg_path = FindPackageShare("cassiopeia_description")

    use_sim = LaunchConfiguration("use_sim")
    use_fake_hardware = LaunchConfiguration("use_fake_hardware")
    fake_sensor_commands = LaunchConfiguration("fake_sensor_commands")

    xacro_path = PathJoinSubstitution([pkg_path, "urdf", "cassiopeia.urdf.xacro"])
    assert os.path.exists(xacro_path ...
(more)
edit flag offensive delete link more

Comments

what does your launch look like?

Because I get the error output like this

[wheel_velocity_controller-2] The passed value needs to be a dictionary in YAML format
[ERROR] [wheel_velocity_controller-2]: process has died [pid 1009427, exit code 1, cmd 'ros2 topic pub /joint_states sensor_msgs/msg/JointState "{data: True}"']

in my launch, it is:

return launch.LaunchDescription([
    launch.actions.ExecuteProcess(cmd=['gazebo', '--verbose', '-s', 'libgazebo_ros_factory.so'], output='screen'),
    launch.actions.ExecuteProcess(
        name='wheel_velocity_controller',
        cmd = ['ros2', 'topic', 'pub', '/joint_states', 'sensor_msgs/msg/JointState', '"{data: True}"'],
        output = 'screen',
        shell='True'
  ),
kak13 gravatar image kak13  ( 2021-08-24 12:27:57 -0500 )edit
1

I updated my answer with the launch file, because it is no big for a comment. (Update 1)

Darkproduct gravatar image Darkproduct  ( 2021-08-24 13:18:48 -0500 )edit
1

You can use urdf only, but I would advice to use it, if you want to do more then just a small demo.

Darkproduct gravatar image Darkproduct  ( 2021-08-24 13:23:51 -0500 )edit
1

I would advice to look at the ROS2 Control Demo pkg, that I linked above. Mine is basically a copy pasta of that and other examples/tutorials. Unfortunately, the ROS2 Documentation of most packages (even of the core packages, like ros_launch) are absolute garbage right now.

Darkproduct gravatar image Darkproduct  ( 2021-08-24 13:28:30 -0500 )edit

I followed your launch and I'm having a lot of issues now. I will take a break then resume on this one.

I merged my launch with the launch you provide. I updated my launch in my post as well

kak13 gravatar image kak13  ( 2021-08-24 15:09:02 -0500 )edit

I added Update 2 and I think thats all I can give you. If you have smaller questions regarding this, open a new question. My answer is already too long and not fun to edit.

Darkproduct gravatar image Darkproduct  ( 2021-08-24 18:05:36 -0500 )edit

Thank you so much!!!

I end up have a last question after trying to fix this issue for almost 2 hours now lol I'm going to make a new question! I'm going to mark your question as an answer since it answers the question!

I wish I could cashapp you to donate u 50 dollars! haha

kak13 gravatar image kak13  ( 2021-08-24 22:23:48 -0500 )edit
1

I'm glad I could help. I know the ROS2 Documentation is lacking and many packages don't even provide one.

Darkproduct gravatar image Darkproduct  ( 2021-08-25 03:54:05 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2021-08-10 16:09:04 -0500

Seen: 1,428 times

Last updated: Aug 24 '21