ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
Based on the ROS2 service/client tutorial 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:
Start gazebo:
gazebo --verbose -s libgazebo_ros_factory.so
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>"
2 | No.2 Revision |
Based on the ROS2 service/client tutorial 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:
Start gazebo:
gazebo --verbose -s libgazebo_ros_factory.so
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>"