ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
I read the tutorial [..]
You don't mention which tutorial you read. I guess it's Writing a Simple Service and Client (Python).
I think I can explain my problem better using the tutorial example. I would like to adapt the .srv there.
int64 a int64 b --- int64 sum int64 multi
multi should just be the product a * b but I do not get the value transferred. How would you have to adapt the code from the example to send two values?
In ROS 1, .srv
s are the input to a code-generation process which results in (in this case) a Python package with several modules. The modules contain classes which represent the various parts of either messages, services or actions.
For a service definition, the top part (above the ---
) gets used to generate the request, while the bottom part (below the ---
) generates the response. See Service definitions, request messages, and response messages for a more detailed description.
Service server handlers (ie: the callback you register when instantiating a rospy.Service
) get passed the incoming request as the first argument to the function you registered. That function is expected to return an instance of the response, and that return value will then be passed back to the client.
The tutorial you mention shows how this is done:
def handle_add_two_ints(req): ... return AddTwoIntsResponse(...)
req
is an instance of AddTwoIntsRequest
and the response is an instance of AddTwoIntsResponse
.
I don't understand how to get multiple response in one service.
Where I believe the confusion comes from is the particular style used in the tutorial:
return AddTwoIntsResponse(req.a + req.b)
this shows Python's positional arguments used to pass the result of the addition (of the service request fields a
and b
) to the constructor of the AddTwoIntsResponse
instance. This makes it look like only a single return value is possible, but that's not the case: the AddTwoIntsResponse
constructor just takes a single argument, as the service definition (as defined in the .srv
file), only has a single field in the response part (ie: sum
).
A different style (ie: keyword arguments) would perhaps have already provided a hint on how to deal with multiple fields in the response part. The following is equivalent to what the tutorial shows:
return AddTwoIntsResponse(sum=(req.a + req.b))
this explicitly refers to the service field sum
.
In the same way you can provide values for any of the other fields which may be part of a service response. Just specify their name and provide a value.
Another alternative would have been:
resp = AddTwoIntsResponse()
resp.sum = req.a + req.b
return resp
This results in the exact same AddTwoIntsResponse
instance being returned to the client.
How to populate other fields in a service response should be clear now. To use your example (with multi
a second field in the response object):
return AddTwoIntsResponse(sum=(req.a + req.b), multi=(req.a * req.b))
or:
resp = AddTwoIntsResponse()
resp.sum = req.a + req.b
resp.multi = req.a * req.b
return resp
Note: you cannot use AddTwoIntsResponse(req.a + req.b, req.a * req.b)
as that's explicitly not supported (only services with single-argument responses can use that shortcut).
Refer to wiki/rospy: Providing services for more information on the supported ways of returning service responses from service server callbacks.
2 | No.2 Revision |
I read the tutorial [..]
You don't mention which tutorial you read. I guess it's Writing a Simple Service and Client (Python).
I think I can explain my problem better using the tutorial example. I would like to adapt the .srv there.
int64 a int64 b --- int64 sum int64 multi
multi should just be the product a * b but I do not get the value transferred. How would you have to adapt the code from the example to send two values?
In ROS 1, .srv
s are the input to a code-generation process which results in (in this case) a Python package with several modules. The modules contain classes which represent the various parts of either messages, services or actions.
For a service definition, the top part (above the ---
) gets used to generate the request, while the bottom part (below the ---
) generates the response. See Service definitions, request messages, and response messages for a more detailed description.
Service server handlers (ie: the callback you register when instantiating a rospy.Service
) get passed the incoming request as the first argument to the function you registered. That function is expected to return an instance of the response, and that return value will then be passed back to the client.
The tutorial you mention shows how this is done:
def handle_add_two_ints(req): ... return AddTwoIntsResponse(...)
req
is an instance of AddTwoIntsRequest
and the response is an instance of AddTwoIntsResponse
.
I don't understand how to get multiple response in one service.
Where I believe the confusion comes from is the particular style used in the tutorial:
return AddTwoIntsResponse(req.a + req.b)
this shows Python's positional arguments used to pass the result of the addition (of the service request fields a
and b
) to the constructor of the AddTwoIntsResponse
instance. This makes it look like only a single return value is possible, but that's not the case: the AddTwoIntsResponse
constructor just takes a single argument, as the service definition (as defined in the .srv
file), only has a single field in the response part (ie: sum
).). But that's just how that service is defined.
A different style (ie: keyword arguments) would perhaps have already provided a hint on how to deal with multiple fields in the response part. The following is equivalent to what the tutorial shows:
return AddTwoIntsResponse(sum=(req.a + req.b))
this explicitly refers to the service field sum
.
In the same way you can provide values for any of the other fields which may be part of a service response. Just specify their name and provide a value.
Another alternative would have been:
resp = AddTwoIntsResponse()
resp.sum = req.a + req.b
return resp
This results in the exact same AddTwoIntsResponse
instance being returned to the client.
How to populate other fields in a service response should be clear now. To use your example (with multi
a second field in the response object):
return AddTwoIntsResponse(sum=(req.a + req.b), multi=(req.a * req.b))
or:
resp = AddTwoIntsResponse()
resp.sum = req.a + req.b
resp.multi = req.a * req.b
return resp
Note: you cannot use AddTwoIntsResponse(req.a + req.b, req.a * req.b)
as that's explicitly not supported (only services with single-argument responses can use that shortcut).
Refer to wiki/rospy: Providing services for more information on the supported ways of returning service responses from service server callbacks.
3 | No.3 Revision |
I read the tutorial [..]
You don't mention which tutorial you read. I guess it's Writing a Simple Service and Client (Python).
I think I can explain my problem better using the tutorial example. I would like to adapt the .srv there.
int64 a int64 b --- int64 sum int64 multi
multi should just be the product a * b but I do not get the value transferred. How would you have to adapt the code from the example to send two values?
In ROS 1, .srv
s are the input to a code-generation process which results in (in this case) a Python package with several modules. The modules contain classes which represent the various parts of either messages, services or actions.
For a service definition, the top part (above the ---
) gets used to generate the request, while the bottom part (below the ---
) generates the response. See Service definitions, request messages, and response messages for a more detailed description.
Service server handlers (ie: the callback you register when instantiating a rospy.Service
) get passed the incoming request as the first argument to the function you registered. That function is expected to return an instance of the response, and that return value will then be passed back to the client.
The tutorial you mention shows how this is done:
def handle_add_two_ints(req): ... return AddTwoIntsResponse(...)
req
is an instance of AddTwoIntsRequest
and the response is an instance of AddTwoIntsResponse
.
I don't understand how to get multiple response in one service.
Where I believe the confusion comes from is the particular style used in the tutorial:
return AddTwoIntsResponse(req.a + req.b)
this shows Python's positional arguments used to pass the result of the addition (of the service request fields a
and b
) to the constructor of the AddTwoIntsResponse
instance. This makes it look like only a single return value is possible, but that's not the case: the AddTwoIntsResponse
constructor just takes a single argument, as the service definition (as defined in the .srv
file), only has a single field in the response part (ie: sum
). But that's just how that service is defined.
A different style (ie: keyword arguments) arguments) would perhaps have already provided a hint on how to deal with multiple fields in the response part. The following is equivalent to what the tutorial shows:
return AddTwoIntsResponse(sum=(req.a + req.b))
this explicitly refers to the service field sum
.
In the same way you can provide values for any of the other fields which may be part of a service response. Just specify their name and provide a value.
Another alternative would have been:
resp = AddTwoIntsResponse()
resp.sum = req.a + req.b
return resp
This results in the exact same AddTwoIntsResponse
instance being returned to the client.
How to populate other fields in a service response should be clear now. To use your example (with multi
a second field in the response object):
return AddTwoIntsResponse(sum=(req.a + req.b), multi=(req.a * req.b))
or:
resp = AddTwoIntsResponse()
resp.sum = req.a + req.b
resp.multi = req.a * req.b
return resp
Note: you cannot use AddTwoIntsResponse(req.a + req.b, req.a * req.b)
as that's explicitly not supported (only services with single-argument responses can use that shortcut).
Refer to wiki/rospy: Providing services for more information on the supported ways of returning service responses from service server callbacks.