6.5 Calling Services

Calling services from URScript requires creating service client handle. ros_service_client_factory() method can be used in similar fashion to publisher/subscriber factories where service name, message type, and QoS parameters are supplied.

wait_for_service(), and call() methods allow for typical interaction. Both methods take optional timeout parameter - if not specified then functions are blocking indefinitely. Otherwise they block until timeout is reached. Timeout is specified in seconds.

bool wait_for_service(number timeout): Wait until service is available

struct call(struct request, number timeout): Call service with data specified in request structure. Return structure with service reply. NOTE: returned structure is different depending if timeout is specified. See below examples for more details.

*close(): *closes handle, and releases all resources.

Service call with timeout example

# Place the following somewhere it will only be executed once, such as Before Start
client = ros_service_client_factory("/test", "std_srvs/srv/Empty")
 
# Create data structure corresponding to service call type (empty structure in this case)
request = struct()
 
# Wait for 5s for service to be available
success = client.wait_for_service(5.0)
popup(success)
 
if(success):
  # calling service with timeout - unblocks after timeout, but returned structure is more difficult to process.
  result = client.call(request, 1.0)
  # result is a struct with 2 members: struct(success, reply)
  # success: bool True if call succeeded, or False if it timed-out
  # reply: depending on the success
  #   - success == True - reply contains structure with actual service reply
  #   - success == False - reply contains empty struct
  popup("Service call result: " + result.to_string())
 
  # blocking service call
  # Call service, block until service replies
  reply = client.call(request)
  # reply contains structure with members specified in service message type.
  popup("Service reply: " + reply.to_string())
end

Before making a service call, it might be useful to check whether the service is available or not. In the example above, before the ROS2 service call, wait_for_service() function is called to make sure of service availability. Thus, the call will wait for service for 5 seconds. If the given service is not available for 5 seconds, wait_for_service() function will return false. Otherwise, it will return true.