Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Refactor spawn_model script #730

Merged
merged 5 commits into from
Jul 6, 2018

Conversation

kev-the-dev
Copy link
Collaborator

@kev-the-dev kev-the-dev commented May 25, 2018

Implement #729:

  • parse arguments using argparse (much less code and easier to read than manually parsing arguments)
  • Fix spawn_model logging issue #597 (argument parsing errors are printed instead of roslogged as they occur before node initialization)
  • Remove deprecated -gazebo option
  • Remove references to trimesh format and options (they were never parsed in the script)
  • Exit with non-zero exit code on failure so scripts can see if spawn_model succeeded
  • Initialize node anonymously so multiple instances can run simultaneously
  • Various style (pep8 compliant) / readability changes
  • Update the comments on a service which was inaccurate
  • Add option to read model from stdin (originally proposed in add option to input xml from stdin to spawn_model #603)
  • Use python standard library xml to parse xml string to verify correctness, allow for more robust -package_to_model flag (issue 449)

I've tested all of the options on my own machine, not sure if any CI tests involve this script.

Old help message:

kallen@bender:~$ rosrun gazebo_ros spawn_model -h
SpawnModel script started
Commands:
    -[urdf|sdf|trimesh|gazebo] - specify incoming xml is urdf, sdf or trimesh format. gazebo arg is deprecated in ROS Hydro
    -[file|param|database] [<file_name>|<param_name>|<model_name>] - source of the model xml or the trimesh file
    -model <model_name> - name of the model to be spawned.
    -reference_frame <entity_name> - optional: name of the model/body where initial pose is defined.
                                     If left empty or specified as "world", gazebo world frame is used.
    -gazebo_namespace <gazebo ros_namespace> - optional: ROS namespace of gazebo offered ROS interfaces.  Defaults to /gazebo/ (e.g. /gazebo/spawn_model).
    -robot_namespace <robot ros_namespace> - optional: change ROS namespace of gazebo-plugins.
    -unpause - optional: !!!Experimental!!! unpause physics after spawning model
    -wait - optional: !!!Experimental!!! wait for model to exist
    -trimesh_mass <mass in kg> - required if -trimesh is used: linear mass
    -trimesh_ixx <moment of inertia in kg*m^2> - required if -trimesh is used: moment of inertia about x-axis
    -trimesh_iyy <moment of inertia in kg*m^2> - required if -trimesh is used: moment of inertia about y-axis
    -trimesh_izz <moment of inertia in kg*m^2> - required if -trimesh is used: moment of inertia about z-axis
    -trimesh_gravity <bool> - required if -trimesh is used: gravity turned on for this trimesh model
    -trimesh_material <material name as a string> - required if -trimesh is used: E.g. Gazebo/Blue
    -trimesh_name <link name as a string> - required if -trimesh is used: name of the link containing the trimesh
    -x <x in meters> - optional: initial pose, use 0 if left out
    -y <y in meters> - optional: initial pose, use 0 if left out
    -z <z in meters> - optional: initial pose, use 0 if left out
    -R <roll in radians> - optional: initial pose, use 0 if left out
    -P <pitch in radians> - optional: initial pose, use 0 if left out
    -Y <yaw in radians> - optional: initial pose, use 0 if left out
    -J <joint_name joint_position> - optional: initialize the specified joint at the specified value
    -package_to_model - optional: convert urdf <mesh filename="package://..." to <mesh filename="model://..."
    -b - optional: bond to gazebo and delete the model when this program is interrupted

New help message:

kallen@bender:~$ rosrun gazebo_ros spawn_model -h
usage: spawn_model [-h] (-urdf | -sdf)
                   (-file FILE_NAME | -param PARAM_NAME | -database MODEL_NAME)
                   -model MODEL_NAME [-reference_frame REFERENCE_FRAME]
                   [-gazebo_namespace GAZEBO_NAMESPACE]
                   [-robot_namespace ROBOT_NAMESPACE] [-unpause]
                   [-wait MODEL_NAME] [-x X] [-y Y] [-z Z] [-R R] [-P P]
                   [-Y Y] [-J JOINT_NAME JOINT_POSITION] [-package_to_model]
                   [-b]

Spawn a model in gazebo using the ROS API

optional arguments:
  -h, --help            show this help message and exit
  -urdf                 Incoming xml is in urdf format
  -sdf                  Incoming xml is in sdf format
  -file FILE_NAME       Load model xml from file
  -param PARAM_NAME     Load model xml from ROS parameter
  -database MODEL_NAME  Load model XML from specified model in Gazebo Model
                        Database
  -model MODEL_NAME     Name of model to spawn
  -reference_frame REFERENCE_FRAME
                        Name of the model/body where initial pose is defined.
                        If left empty or specified as "world", gazebo world
                        frame is used
  -gazebo_namespace GAZEBO_NAMESPACE
                        ROS namespace of gazebo offered ROS interfaces.
                        Defaults to /gazebo/
  -robot_namespace ROBOT_NAMESPACE
                        change ROS namespace of gazebo-plugins
  -unpause              !!!Experimental!!! unpause physics after spawning
                        model
  -wait MODEL_NAME      !!!Experimental!!! wait for model to exist
  -x X                  x component of initial position, meters
  -y Y                  y component of initial position, meters
  -z Z                  z component of initial position, meters
  -R R                  roll angle of initial orientation, radians
  -P P                  pitch angle of initial orientation, radians
  -Y Y                  yaw angle of initial orientation, radians
  -J JOINT_NAME JOINT_POSITION
                        initialize the specified joint at the specified
                        position
  -package_to_model     convert urdf <mesh filename="package://..." to <mesh
                        filename="model://..."
  -b                    bond to gazebo and delete the model when this program
                        is interrupted

Copy link
Contributor

@j-rivero j-rivero left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Kevin, this is awesome! some code quality finally to spawn_model. I was testing different options and did not make it to fail. If you could please include the following patch to fix some problems in tests, that would be great:

diff --git a/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/battery_block.xacro b/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/battery_block.xacro
index c14674e..f6b6fe8 100644
--- a/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/battery_block.xacro
+++ b/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/battery_block.xacro
@@ -1,6 +1,6 @@
 <?xml version="1.0"?>
 <robot xmlns:xacro="http://ros.org/wiki/xacro">
-  <property name="M_PI" value="3.1415926535897931" />
+  <xacro:property name="M_PI" value="3.1415926535897931" />
 
   <xacro:macro name="battery_block" params="name parent x y z mass">
 
diff --git a/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/inertia_tensors.xacro b/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/inertia_tensors.xacro
index d33f1ca..df6e312 100644
--- a/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/inertia_tensors.xacro
+++ b/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/inertia_tensors.xacro
@@ -3,7 +3,7 @@
   see https://github.com/uos/uos_tools/blob/fuerte/uos_common_urdf/common.xacro and
   see http://answers.gazebosim.org/question/4372/the-inertia-matrix-explained/ -->
 <robot xmlns:xacro="http://ros.org/wiki/xacro">
-  <property name="M_PI" value="3.1415926535897931" />
+  <xacro:property name="M_PI" value="3.1415926535897931" />
 
   <!-- see https://secure.wikimedia.org/wikipedia/en/wiki/List_of_moment_of_inertia_tensors -->
 
@@ -42,7 +42,7 @@
   <xacro:macro name="sphere_inertial_with_origin" params="radius mass *origin">
     <inertial>
       <mass value="${mass}" />
-      <insert_block name="origin" />
+      <xacro:insert_block name="origin" />
       <inertia ixx="${0.4 * mass * radius * radius}" ixy="0.0" ixz="0.0"
         iyy="${0.4 * mass * radius * radius}" iyz="0.0"
         izz="${0.4 * mass * radius * radius}" />
@@ -52,7 +52,7 @@
   <xacro:macro name="cylinder_inertial_with_origin" params="radius length mass *origin">
     <inertial>
       <mass value="${mass}" />
-      <insert_block name="origin" />
+      <xacro:insert_block name="origin" />
       <inertia ixx="${0.0833333 * mass * (3 * radius * radius + length * length)}" ixy="0.0" ixz="0.0"
         iyy="${0.0833333 * mass * (3 * radius * radius + length * length)}" iyz="0.0"
         izz="${0.5 * mass * radius * radius}" />
@@ -62,7 +62,7 @@
   <xacro:macro name="box_inertial_with_origin" params="x y z mass *origin">
     <inertial>
       <mass value="${mass}" />
-      <insert_block name="origin" />
+      <xacro:insert_block name="origin" />
       <inertia ixx="${0.0833333 * mass * (y*y + z*z)}" ixy="0.0" ixz="0.0"
         iyy="${0.0833333 * mass * (x*x + z*z)}" iyz="0.0"
         izz="${0.0833333 * mass * (x*x + y*y)}" />
diff --git a/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_chassis.xacro b/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_chassis.xacro
index 4daddb6..77f4a55 100644
--- a/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_chassis.xacro
+++ b/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_chassis.xacro
@@ -1,6 +1,6 @@
 <?xml version="1.0"?>
 <robot xmlns:xacro="http://ros.org/wiki/xacro">
-  <property name="M_PI" value="3.1415926535897931" />
+  <xacro:property name="M_PI" value="3.1415926535897931" />
 
   <xacro:macro name="pioneer_chassis" params="name parent xyz rpy meshes">
 
diff --git a/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_sonar.xacro b/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_sonar.xacro
index 5bdf7a8..a6c2fcc 100644
--- a/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_sonar.xacro
+++ b/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_sonar.xacro
@@ -1,6 +1,6 @@
 <?xml version="1.0"?>
 <robot xmlns:xacro="http://ros.org/wiki/xacro">
-  <property name="M_PI" value="3.1415926535897931" />
+  <xacro:property name="M_PI" value="3.1415926535897931" />
 
   <xacro:macro name="pioneer_sonar" params="name parent xyz rpy meshes">
 
diff --git a/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_swivel.xacro b/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_swivel.xacro
index 1cba807..ed9c5a0 100644
--- a/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_swivel.xacro
+++ b/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_swivel.xacro
@@ -1,6 +1,6 @@
 <?xml version="1.0"?>
 <robot xmlns:xacro="http://ros.org/wiki/xacro">
-  <property name="M_PI" value="3.1415926535897931" />
+  <xacro:property name="M_PI" value="3.1415926535897931" />
 
   <xacro:macro name="pioneer_swivel" params="parent xyz rpy meshes">
 
diff --git a/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_wheel.xacro b/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_wheel.xacro
index 9c0f87e..2d0bf2d 100644
--- a/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_wheel.xacro
+++ b/gazebo_plugins/test/multi_robot_scenario/xacro/p3dx/pioneer3dx_wheel.xacro
@@ -1,7 +1,7 @@
 <?xml version="1.0"?>
 <robot
   xmlns:xacro="http://ros.org/wiki/xacro">
-  <property name="M_PI" value="3.1415926535897931" />
+  <xacro:property name="M_PI" value="3.1415926535897931" />
 
   <xacro:macro name="pioneer_wheel" params="side parent xyz rpy radius meshes">
 
diff --git a/gazebo_plugins/test/tricycle_drive/xacro/tricycle/inertia_tensors.xacro b/gazebo_plugins/test/tricycle_drive/xacro/tricycle/inertia_tensors.xacro
index ed07e4e..8d0e15e 100644
--- a/gazebo_plugins/test/tricycle_drive/xacro/tricycle/inertia_tensors.xacro
+++ b/gazebo_plugins/test/tricycle_drive/xacro/tricycle/inertia_tensors.xacro
@@ -3,7 +3,7 @@
   see https://github.com/uos/uos_tools/blob/fuerte/uos_common_urdf/common.xacro and
   see http://answers.gazebosim.org/question/4372/the-inertia-matrix-explained/ -->
 <robot xmlns:xacro="http://ros.org/wiki/xacro">
-  <property name="M_PI" value="3.1415926535897931" />
+  <xacro:property name="M_PI" value="3.1415926535897931" />
 
   <!-- see https://secure.wikimedia.org/wikipedia/en/wiki/List_of_moment_of_inertia_tensors -->
 
@@ -42,7 +42,7 @@
   <xacro:macro name="sphere_inertial_with_origin" params="radius mass *origin">
     <inertial>
       <mass value="${mass}" />
-      <insert_block name="origin" />
+      <xacro:insert_block name="origin" />
       <inertia ixx="${0.4 * mass * radius * radius}" ixy="0.0" ixz="0.0"
         iyy="${0.4 * mass * radius * radius}" iyz="0.0"
         izz="${0.4 * mass * radius * radius}" />
@@ -52,7 +52,7 @@
   <xacro:macro name="cylinder_inertial_with_origin" params="radius length mass *origin">
     <inertial>
       <mass value="${mass}" />
-      <insert_block name="origin" />
+      <xacro:insert_block name="origin" />
       <inertia ixx="${0.0833333 * mass * (3 * radius * radius + length * length)}" ixy="0.0" ixz="0.0"
         iyy="${0.0833333 * mass * (3 * radius * radius + length * length)}" iyz="0.0"
         izz="${0.5 * mass * radius * radius}" />
diff --git a/gazebo_plugins/test/tricycle_drive/xacro/tricycle/tricycle_body.xacro b/gazebo_plugins/test/tricycle_drive/xacro/tricycle/tricycle_body.xacro
index a6ea3db..2c88aa7 100644
--- a/gazebo_plugins/test/tricycle_drive/xacro/tricycle/tricycle_body.xacro
+++ b/gazebo_plugins/test/tricycle_drive/xacro/tricycle/tricycle_body.xacro
@@ -1,8 +1,8 @@
 <?xml version="1.0"?>
 <robot xmlns:xacro="http://www.ros.org/wiki/xacro">
-  <property name="M_PI" value="3.1415926535897931" />
-  <property name="radius_actuated_wheel" value="0.135" />
-  <property name="radius_encoder_wheel" value="0.135" />
+  <xacro:property name="M_PI" value="3.1415926535897931" />
+  <xacro:property name="radius_actuated_wheel" value="0.135" />
+  <xacro:property name="radius_encoder_wheel" value="0.135" />
 
   <xacro:include filename="inertia_tensors.xacro"/>
   <xacro:include filename="tricycle_chassis.xacro"/>
diff --git a/gazebo_plugins/test/tricycle_drive/xacro/tricycle/tricycle_chassis.xacro b/gazebo_plugins/test/tricycle_drive/xacro/tricycle/tricycle_chassis.xacro
index bced5fa..13e02c6 100644
--- a/gazebo_plugins/test/tricycle_drive/xacro/tricycle/tricycle_chassis.xacro
+++ b/gazebo_plugins/test/tricycle_drive/xacro/tricycle/tricycle_chassis.xacro
@@ -1,9 +1,9 @@
 <?xml version="1.0"?>
 <robot xmlns:xacro="http://ros.org/wiki/xacro">
-  <property name="M_PI" value="3.1415926535897931" />
-  <property name="DX" value="2.500" />
-  <property name="DY" value="0.60" />
-  <property name="DZ" value="0.1" />
+  <xacro:property name="M_PI" value="3.1415926535897931" />
+  <xacro:property name="DX" value="2.500" />
+  <xacro:property name="DY" value="0.60" />
+  <xacro:property name="DZ" value="0.1" />
 
   <xacro:macro name="tricycle_chassis" params="name parent xyz rpy meshes">
 
diff --git a/gazebo_plugins/test/tricycle_drive/xacro/tricycle/wheel.xacro b/gazebo_plugins/test/tricycle_drive/xacro/tricycle/wheel.xacro
index 3738ee3..5fb440a 100644
--- a/gazebo_plugins/test/tricycle_drive/xacro/tricycle/wheel.xacro
+++ b/gazebo_plugins/test/tricycle_drive/xacro/tricycle/wheel.xacro
@@ -1,7 +1,7 @@
 <?xml version="1.0"?>
 <robot
   xmlns:xacro="http://ros.org/wiki/xacro">
-  <property name="M_PI" value="3.1415926535897931" />
+  <xacro:property name="M_PI" value="3.1415926535897931" />
 
   <xacro:macro name="wheel" params="name parent xyz rpy radius length meshes">
 
diff --git a/gazebo_plugins/test/tricycle_drive/xacro/tricycle/wheel_actuated.xacro b/gazebo_plugins/test/tricycle_drive/xacro/tricycle/wheel_actuated.xacro
index 1ae0f39..a338397 100644
--- a/gazebo_plugins/test/tricycle_drive/xacro/tricycle/wheel_actuated.xacro
+++ b/gazebo_plugins/test/tricycle_drive/xacro/tricycle/wheel_actuated.xacro
@@ -1,6 +1,6 @@
 <?xml version="1.0"?>
 <robot xmlns:xacro="http://ros.org/wiki/xacro">
-  <property name="M_PI" value="3.1415926535897931" />
+  <xacro:property name="M_PI" value="3.1415926535897931" />
 
   <xacro:macro name="wheel_actuated" params="name parent xyz rpy radius length meshes">
 
diff --git a/gazebo_plugins/test2/large_models/large_model.launch b/gazebo_plugins/test2/large_models/large_model.launch
index e33de64..d70cfbe 100644
--- a/gazebo_plugins/test2/large_models/large_model.launch
+++ b/gazebo_plugins/test2/large_models/large_model.launch
@@ -9,19 +9,19 @@
   </group>
 
   <!-- start empty world -->
-  <node name="empty_world_server" pkg="gazebo" type="gazebo" args="-u $(find gazebo_tests)/test/large_models/large_models.world" respawn="false" output="screen"/>
+  <node name="empty_world_server" pkg="gazebo_ros" type="gazebo" args="-u $(find gazebo_plugins)/test/large_models/large_models.world" respawn="false" output="screen"/>
 
   <!-- start gui -->
   <group if="$(arg gui)">
-    <node name="gazebo_gui" pkg="gazebo" type="gui" respawn="false" output="screen"/>
+    <node name="gazebo_gui" pkg="gazebo_ros" type="gui" respawn="false" output="screen"/>
   </group>
 
   <!-- send urdf to param server -->
   <!--
-  <param name="robot_description" textfile="$(find gazebo_tests)/test/pendulum.model" />
+  <param name="robot_description" textfile="$(find gazebo_plugins)/test/pendulum.model" />
   -->
-  <param name="robot_description" command="$(find xacro)/xacro.py '$(find gazebo_tests)/test/large_models/large_model.urdf.xacro'" />
+  <param name="robot_description" command="$(find xacro)/xacro.py '$(find gazebo_plugins)/test2/large_models/large_model.urdf.xacro'" />
   <!-- push robot_description to factory and spawn robot in gazebo -->
-  <node name="spawn_pr2_model" pkg="gazebo" type="spawn_model" args="$(optenv ROBOT_INITIAL_POSE) -urdf -param robot_description -model pr2" respawn="false" output="screen" />
+  <node name="spawn_pr2_model" pkg="gazebo_ros" type="spawn_model" args="$(optenv ROBOT_INITIAL_POSE) -urdf -param robot_description -model pr2" respawn="false" output="screen" />
 
 </launch>
diff --git a/gazebo_plugins/test2/large_models/large_model.urdf.xacro b/gazebo_plugins/test2/large_models/large_model.urdf.xacro
index 1a48120..0237e79 100644
--- a/gazebo_plugins/test2/large_models/large_model.urdf.xacro
+++ b/gazebo_plugins/test2/large_models/large_model.urdf.xacro
@@ -20,8 +20,8 @@
   -->
   <xacro:macro name="one_link" params="link_name parent *axis *origin material">
     <joint name="${link_name}_joint" type="continuous" >
-      <insert_block name="origin"/>
-      <insert_block name="axis"/>
+      <xacro:insert_block name="origin"/>
+      <xacro:insert_block name="axis"/>
       <parent link="${parent}" />
       <child link="${link_name}" />
       <dynamics damping="0.0" />
diff --git a/gazebo_plugins/test2/large_models/smaller_large_model.urdf.xacro b/gazebo_plugins/test2/large_models/smaller_large_model.urdf.xacro
index a4caa13..d8bf621 100644
--- a/gazebo_plugins/test2/large_models/smaller_large_model.urdf.xacro
+++ b/gazebo_plugins/test2/large_models/smaller_large_model.urdf.xacro
@@ -20,8 +20,8 @@
   -->
   <xacro:macro name="one_link" params="link_name parent *axis *origin material">
     <joint name="${link_name}_joint" type="continuous" >
-      <insert_block name="origin"/>
-      <insert_block name="axis"/>
+      <xacro:insert_block name="origin"/>
+      <xacro:insert_block name="axis"/>
       <parent link="${parent}" />
       <child link="${link_name}" />
       <dynamics damping="100.0" />
diff --git a/gazebo_plugins/test2/spawn_model/spawn_box.launch b/gazebo_plugins/test2/spawn_model/spawn_box.launch
index 6123c56..7ffcde2 100644
--- a/gazebo_plugins/test2/spawn_model/spawn_box.launch
+++ b/gazebo_plugins/test2/spawn_model/spawn_box.launch
@@ -3,8 +3,8 @@
   <!-- start gazebo with an empty plane -->
   <param name="/use_sim_time" value="true" />
 
-  <node name="gazebo" pkg="gazebo" type="gazebo" args="$(find gazebo_tests)/test/worlds/empty.world" respawn="false" output="screen"/>
+  <node name="gazebo" pkg="gazebo_ros" type="gazebo" args="$(find gazebo_plugins)/test/worlds/empty.world" respawn="false" output="screen"/>
 
-  <test test-name="gazebo_tests" pkg="gazebo_tests" type="spawn_box" args="$(find gazebo_tests)/test/urdf/box.urdf" />
+  <test test-name="gazebo_tests" pkg="gazebo_tests" type="spawn_box" args="$(find gazebo_ros)/test2/urdf/box.urdf" />
 
 </launch>
diff --git a/gazebo_plugins/test2/spawn_model/spawn_box_file.launch b/gazebo_plugins/test2/spawn_model/spawn_box_file.launch
index de46c64..e88b93f 100644
--- a/gazebo_plugins/test2/spawn_model/spawn_box_file.launch
+++ b/gazebo_plugins/test2/spawn_model/spawn_box_file.launch
@@ -3,11 +3,11 @@
   <!-- start gazebo with an empty plane -->
   <param name="/use_sim_time" value="true" />
 
-  <node name="gazebo" pkg="gazebo" type="gazebo" args="$(find gazebo_tests)/test/worlds/empty.world" respawn="false" output="screen"/>
+  <node name="gazebo" pkg="gazebo_ros" type="gazebo" args="$(find gazebo_plugins)/test/worlds/empty.world" respawn="false" output="screen"/>
 
   <!-- spawn in gazebo -->
-  <node name="spawn_box" pkg="gazebo" type="spawn_model" args="-urdf -file $(find gazebo_tests)/test/urdf/box.urdf -z 1.0 -model box" respawn="false" output="screen" />
+  <node name="spawn_box" pkg="gazebo_ros" type="spawn_model" args="-urdf -file $(find gazebo_plugins)/test2/urdf/box.urdf -z 1.0 -model box" respawn="false" output="screen" />
 
   <!-- check for model -->
-  <test test-name="gazebo_tests" pkg="gazebo_tests" type="check_model" args="10 box" />
+  <test test-name="gazebo_plugins" pkg="gazebo_plugins" type="check_model" args="10 box" />
 </launch>
diff --git a/gazebo_plugins/test2/spawn_model/spawn_box_param.launch b/gazebo_plugins/test2/spawn_model/spawn_box_param.launch
index 6713191..c630e20 100644
--- a/gazebo_plugins/test2/spawn_model/spawn_box_param.launch
+++ b/gazebo_plugins/test2/spawn_model/spawn_box_param.launch
@@ -3,13 +3,13 @@
   <!-- start gazebo with an empty plane -->
   <param name="/use_sim_time" value="true" />
 
-  <node name="gazebo" pkg="gazebo" type="gazebo" args="$(find gazebo_tests)/test/worlds/empty.world" respawn="false" output="screen"/>
+  <node name="gazebo" pkg="gazebo_ros" type="gazebo" args="$(find gazebo_plugins)/test/worlds/empty.world" respawn="false" output="screen"/>
 
   <!-- send table urdf to param server -->
-  <param name="box_description" command="$(find xacro)/xacro.py $(find gazebo_tests)/test/urdf/box.urdf" />
+  <param name="box_description" command="cat $(find gazebo_plugins)/test2/urdf/box.urdf" />
 
   <!-- spawn in gazebo -->
-  <node name="spawn_box" pkg="gazebo" type="spawn_model" args="-urdf -param box_description -z 1.0 -model box" respawn="false" output="screen" />
+  <node name="spawn_box" pkg="gazebo_ros" type="spawn_model" args="-urdf -param box_description -z 1.0 -model box" respawn="false" output="screen" />
 
   <!-- check for model -->
   <test test-name="gazebo_tests" pkg="gazebo_tests" type="check_model" args="10 box" />

@kev-the-dev
Copy link
Collaborator Author

Thanks for the patch, looks like it worked! I've also tested this extensively so will go ahead and merge

@kev-the-dev kev-the-dev merged commit 337bd13 into ros-simulation:melodic-devel Jul 6, 2018
cohen39 pushed a commit to cohen39/gazebo_ros_pkgs that referenced this pull request Nov 15, 2021
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants