ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
Hi @sisko,
You cannot do that since the definition is not well formed. As well as you cannot do string[][] topic
since only one dimension is supported in msg definition. What you can do to achieve what you want can split into several approaches:
StringArray.msg
string[] topic
And then use it in your srv file like:
TopicList.srv
StringArray topic
---
StringArray[] topics
List item
StringMultiarray
that let you declare a multi dimensional variable. It would be something like:StringMultiarray.msg
std_msgs/MultiArrayLayout layout
string[] data
and TopicList.srv
string[] topic
---
StringMultiArray topics
Hope that can help you solving the problem.
Regards.
2 | No.2 Revision |
Hi @sisko,
You cannot do that since the definition is not well formed. As well as you cannot do string[][] topic
since only one dimension is supported in msg definition. What you can do to achieve what you want can split into several approaches:
StringArray.msg
string[] topic
And then use it in your srv file like:
TopicList.srv
StringArray topic
---
StringArray[] topics
List item
StringMultiarray
that let you declare a multi dimensional variable. It would be something like:StringMultiarray.msg
std_msgs/MultiArrayLayout layout
string[] data
and TopicList.srv
string[] topic
---
StringMultiArray topics
Hope that can help you solving the problem.
Regards.
EDIT:
@sisko, I had implemented a client and service nodes to test your set up and I was able to make it work without errors. I used the follosing code:
For the server_node:
#!/usr/bin/env python
from topics_lister.srv import FetchTopics, FetchTopicsResponse
from topics_lister.msg import Topic
import rospy
def sendTopics(request):
print("_________________________")
msg_topic_1 = Topic('/turtle1/color_sensor', 'turtlesim/Color')
msg_topic_2 = Topic('/client_count', 'std_msgs/Int32')
response = FetchTopicsResponse()
response.topics = [msg_topic_1, msg_topic_2]
return response
def fetch_topics_server():
rospy.init_node('fetch_topics_server')
s = rospy.Service('fetch_topics', FetchTopics, sendTopics)
print ("Serving topics ...")
rospy.spin()
if __name__ == "__main__":
fetch_topics_server()
And fot the client_node:
#!/usr/bin/env python
import sys
import rospy
from topics_lister.srv import *
from topics_lister.msg import *
def fetch_topic_client(data):
rospy.wait_for_service('fetch_topics')
try:
fetch_topics = rospy.ServiceProxy('fetch_topics', FetchTopics)
resp1 = fetch_topics(data)
return resp1.topics
except rospy.ServiceException as e:
print("Service call failed: %s"%e)
def usage():
return "%s [data]"%sys.argv[0]
if __name__ == "__main__":
if len(sys.argv) == 2:
data = sys.argv[1]
else:
print(usage())
sys.exit(1)
print("Requesting topics...")
print(fetch_topic_client("place_holder"))
Since yu only provided the response of the srv I assume the full definition is:
string req_data
---
Topic[] topics
But you can change that easily.
3 | No.3 Revision |
Hi @sisko,
You cannot do that since the definition is not well formed. As well as you cannot do string[][] topic
since only one dimension is supported in msg definition. What you can do to achieve what you want can split into several approaches:
StringArray.msg
string[] topic
And then use it in your srv file like:
TopicList.srv
StringArray topic
---
StringArray[] topics
List item
StringMultiarray
that let you declare a multi dimensional variable. It would be something like:StringMultiarray.msg
std_msgs/MultiArrayLayout layout
string[] data
and TopicList.srv
string[] topic
---
StringMultiArray topics
Hope that can help you solving the problem.
Regards.
EDIT:
@sisko, I had implemented a client and service nodes to test your set up and I was able to make it work without errors. I used the follosing code:
For the server_node:
#!/usr/bin/env python
from topics_lister.srv import FetchTopics, FetchTopicsResponse
from topics_lister.msg import Topic
import rospy
def sendTopics(request):
print("_________________________")
msg_topic_1 = Topic('/turtle1/color_sensor', 'turtlesim/Color')
msg_topic_2 = Topic('/client_count', 'std_msgs/Int32')
response = FetchTopicsResponse()
response.topics = [msg_topic_1, msg_topic_2]
return response
def fetch_topics_server():
rospy.init_node('fetch_topics_server')
s = rospy.Service('fetch_topics', FetchTopics, sendTopics)
print ("Serving topics ...")
rospy.spin()
if __name__ == "__main__":
fetch_topics_server()
And fot the client_node:for the client_node:
#!/usr/bin/env python
import sys
import rospy
from topics_lister.srv import *
from topics_lister.msg import *
def fetch_topic_client(data):
rospy.wait_for_service('fetch_topics')
try:
fetch_topics = rospy.ServiceProxy('fetch_topics', FetchTopics)
resp1 = fetch_topics(data)
return resp1.topics
except rospy.ServiceException as e:
print("Service call failed: %s"%e)
def usage():
return "%s [data]"%sys.argv[0]
if __name__ == "__main__":
if len(sys.argv) == 2:
data = sys.argv[1]
else:
print(usage())
sys.exit(1)
print("Requesting topics...")
print(fetch_topic_client("place_holder"))
Since yu only provided the response of the srv I assume the full definition is:
string req_data
---
Topic[] topics
But you can change that easily.