Skip to content

Commit

Permalink
Remove ROS-specific arguments before passing to argparse (#994)
Browse files Browse the repository at this point in the history
This resolves argparse errors when trying to launch the spawn_entity script as a ROS node.

For example, a launch file like the following wouldn't work without this change:

    <launch>
      <arg name="model_urdf" default="$(find-pkg-share mymodels)/urdf/ball.urdf" />
      <node
        pkg="gazebo_ros"
        exec="spawn_entity.py"
        name="spawner"
        args="-entity foo -file /path/to/my/model/foo.urdf" />
    </launch>

Signed-off-by: Jacob Perron <jacob@openrobotics.org>
  • Loading branch information
jacobperron authored and chapulina committed Sep 12, 2019
1 parent 3df4a45 commit d4927c1
Showing 1 changed file with 2 additions and 1 deletion.
3 changes: 2 additions & 1 deletion gazebo_ros/scripts/spawn_entity.py
Original file line number Diff line number Diff line change
Expand Up @@ -340,7 +340,8 @@ def quaternion_from_euler(roll, pitch, yaw):

def main(args=sys.argv):
rclpy.init(args=args)
spawn_entity_node = SpawnEntityNode(args)
args_without_ros = rclpy.utilities.remove_ros_args(args)
spawn_entity_node = SpawnEntityNode(args_without_ros)
spawn_entity_node.get_logger().info('Spawn Entity started')
exit_code = spawn_entity_node.run()
sys.exit(exit_code)
Expand Down

0 comments on commit d4927c1

Please sign in to comment.