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

spawn model with ROS2 gazebo

asked 2019-02-04 03:42:55 -0500

poonam1120 gravatar image

Hi,

I followed this link and able to spawn the sdf model in gazebo.

https://github.com/ros-simulation/gaz...

But instead of sending sdf model code from command line, can we send just sdf/urdf file ? I tried that but it failed.

When i send complete sdf modem from cmnd lien with spawn_entity, it launched in gazebo. I am trying it on crystal.

Please let me know if anybody is having any clue.

Thanks.

edit retag flag offensive close merge delete

4 Answers

Sort by ยป oldest newest most voted
3

answered 2022-02-15 03:48:38 -0500

Reka gravatar image

updated 2022-02-15 03:53:54 -0500

Based on the ROS2 tutorial: 'Writing a simple service and client (python)' and the work of clyde, I've created a complete ROS2 python client to spawn an entity:

import sys
import rclpy
from gazebo_msgs.srv import SpawnEntity

from rclpy.node import Node


class MinimalClientAsync(Node):

    def __init__(self):
        super().__init__('spawn_entity')
        self.client = self.create_client(SpawnEntity, 'spawn_entity')
        while not self.client.wait_for_service(timeout_sec=1.0):
            self.get_logger().info('service not available, waiting again...')
        self.req = SpawnEntity.Request()

    def send_request(self):
        self.req.name = str(sys.argv[1])
        self.req.xml = str(sys.argv[2])
        self.future = self.client.call_async(self.req)


def main(args=None):
    rclpy.init(args=args)

    minimal_client = MinimalClientAsync()
    minimal_client.send_request()

    while rclpy.ok():
        rclpy.spin_once(minimal_client)
        if minimal_client.future.done():
            try:
                response = minimal_client.future.result()
            except Exception as e:
                minimal_client.get_logger().info(
                    'Service call failed %r' % (e,))
            else:
                minimal_client.get_logger().info(
                    'Test {}'.format(minimal_client.req.xml))
            break

    minimal_client.destroy_node()
    rclpy.shutdown()


if __name__ == '__main__':
    main()

To spawn a sphere in Gazebo:

  1. Start gazebo:

      gazebo --verbose -s libgazebo_ros_factory.so
    
  2. Run the client node:

      ros2 run my_package my_client_name entity_name xml_description
    

    Example usage :

      ros2 run my_package my_client my_model "<?xml version=\"1.0\" ?><sdf version=\"1.5\"><model name=\"will_be_ignored\"><static>true</static><link name=\"link\"><visual name=\"visual\"><geometry><sphere><radius>1.0</radius></sphere></geometry></visual></link></model></sdf>"
    
edit flag offensive delete link more
3

answered 2021-03-29 19:22:19 -0500

808brick gravatar image

I'd like to update this answer for some people, as ROS2 functionality has improved but the documentation has not yet caught up. (To be clear it is March 2021 and I am running ROS 2 Foxy)

If you have a URDF file (note that the syntax for URDF in ROS 2 is slightly different than ROS 1) in your package that you want to spawn into Gazebo, you have to do the following:

1) Launch gazebo (not the standard way, I will elaborate below)
2) Launch the robot state publisher with your URDF file
3) Run thespawn_entity node to spawn your robot into gazebo

Here is how you go about doing it (as individual steps)

1) Create a Launch File for for your robot state publisher, here is an example:

import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node

def generate_launch_description():

  use_sim_time = LaunchConfiguration('use_sim_time', default='false')
  urdf_file_name = 'urdf/camera_bot.xacro'

  print("urdf_file_name : {}".format(urdf_file_name))

  urdf = os.path.join(
      get_package_share_directory('ros2_sim_pkg'),
      urdf_file_name)

  return LaunchDescription([

        DeclareLaunchArgument(
            'use_sim_time',
            default_value='false',
            description='Use simulation (Gazebo) clock if true'),
        Node(
            package='robot_state_publisher',
            executable='robot_state_publisher',
            name='robot_state_publisher',
            output='screen',
            parameters=[{'use_sim_time': use_sim_time}],
            arguments=[urdf])
  ])

In this example I am launching the robot state publisher with a URDF file called camera_bot.xacro (I am using .xacro because I want to reference other XML files, but a standard .urdf or .xml will work all the same) from a package called ros2_sim_pkg. Change the URDF and package names to fit your project.

2) Build your workspace (colcon build)

3) Source your workspace in the terminals you open (source install/setup.bash)

4) Launch gazebo with ros2 launch gazebo_ros gazebo.launch.py

5) Launch the launch file you just created to configure your robot_state_publisher: ros2 launch ros2_sim_pkg cam_bot_world.launch. Make sure to change the package name and launch file name to match yours.

6) Run the URDF spawner node: ros2 run gazebo_ros spawn_entity.py -topic /robot_description -entity my_cam_bot`

The entity name will be the name of your model within gazebo, so feel free to change "my_cam_bot" to whatever you want. It will automatically spawn at the origin, so if you do not want this, you can check out the other parameters here: https://github.com/ros-simulation/gazebo_ros_pkgs/blob/foxy/gazebo_ros/scripts/spawn_entity.py#L51

And with that you should have gazebo running with your URDF spawned in at the origin. I do not have Karma points so I can not show you a picture of it working unfortunately.

You can feel free to combine all these steps into one big launch file for convenience, but I just wanted to illustrate the process order so it was more understandable.

Hope this helps.

edit flag offensive delete link more

Comments

For those this works, but model tree is created in gazebo but robot not visible. Try adding absolute path for mesh in urdf file.

Jeffin Johny gravatar image Jeffin Johny  ( 2022-08-30 21:55:20 -0500 )edit
2

answered 2019-03-13 13:21:02 -0500

clyde gravatar image

Following tfoote's advice, here is an example:

import sys
import rclpy
from gazebo_msgs.srv import SpawnEntity


def request_spawn(xml: str):
    rclpy.init()
    node = rclpy.create_node('spawn_entity')
    client = node.create_client(SpawnEntity, 'spawn_entity')
    if not client.service_is_ready():
        client.wait_for_service()
    request = SpawnEntity.Request()
    request.xml = xml
    future = client.call_async(request)
    rclpy.spin_until_future_complete(node, future)
    if future.result() is not None:
        print('response: %r' % future.result())
    else:
        raise RuntimeError('exception while calling service: %r' % future.exception())
    node.destroy_node()
    rclpy.shutdown()


if len(sys.argv) < 2:
    print('usage: ros2 run my_package my_node.py -- example.urdf')
    sys.exit(1)

f = open(sys.argv[1], 'r')
request_spawn(f.read())
edit flag offensive delete link more
1

answered 2019-02-04 11:30:17 -0500

tfoote gravatar image

updated 2019-03-13 15:50:06 -0500

The examples are using generic command line tools. If you want to send from a file you can probably set it up to pipe the arguments into the rosservice call using xargs. But more likely I'd recommend writing the few line rclpy script to load the file and call the service call. If you'd like to contribute a generic version of that helper script to the gazebo_ros_pkgs that would be even better.

edit flag offensive delete link more

Question Tools

5 followers

Stats

Asked: 2019-02-04 03:42:55 -0500

Seen: 8,510 times

Last updated: Feb 15 '22