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

gazebo_ros: Fix spawn_entity.py model removal binding #1475

Open
wants to merge 2 commits into
base: ros2
Choose a base branch
from
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
34 changes: 15 additions & 19 deletions gazebo_ros/scripts/spawn_entity.py
Original file line number Diff line number Diff line change
Expand Up @@ -256,11 +256,20 @@ def entity_xml_cb(msg):
if self.args.bond:
self.get_logger().info(
'Waiting for shutdown to delete entity [{}]'.format(self.args.entity))

self.clientDeletion = self.create_client(
DeleteEntity, '%s/delete_entity' % self.args.gazebo_namespace)
if not self.clientDeletion.wait_for_service(timeout_sec=self.args.timeout):
self.get_logger().error(
'Service %s/delete_entity unavailable. Was Gazebo started with GazeboRosFactory?' %
(self.args.gazebo_namespace))

try:
rclpy.spin(self)
except KeyboardInterrupt:
self.get_logger().info('Ctrl-C detected')
self._delete_entity()
finally:
self._delete_entity()

return 0

Expand Down Expand Up @@ -296,24 +305,11 @@ def _spawn_entity(self, entity_xml, initial_pose, timeout=5.0):
def _delete_entity(self):
# Delete entity from gazebo on shutdown if bond flag enabled
self.get_logger().info('Deleting entity [{}]'.format(self.args.entity))
client = self.create_client(
DeleteEntity, '%s/delete_entity' % self.args.gazebo_namespace)
if client.wait_for_service(timeout_sec=self.args.timeout):
req = DeleteEntity.Request()
req.name = self.args.entity
self.get_logger().info(
'Calling service %s/delete_entity' % self.args.gazebo_namespace)
srv_call = client.call_async(req)
while rclpy.ok():
if srv_call.done():
self.get_logger().info(
'Deleting status: %s' % srv_call.result().status_message)
break
rclpy.spin_once(self)
else:
self.get_logger().error(
'Service %s/delete_entity unavailable. ' +
'Was Gazebo started with GazeboRosFactory?')
req = DeleteEntity.Request()
req.name = self.args.entity
self.get_logger().info(
'Calling service %s/delete_entity' % self.args.gazebo_namespace)
self.clientDeletion.call(req)

# def _set_model_configuration(self, joint_names, joint_positions):
# self.get_logger().info(
Expand Down