ROS1
결론 :
spin을 돌릴 필요가 없다.
SERVER 는 블럭해주기만 하면 되고
CLIENT 는 그냥 req 날리고 res 기다린다.
이유 :
rospy에서 spin 은 'roscore' 가 켜졌는지 확인하고
'roscore'가 종료 될때 까지 blocking 루프 돌리는게 다이기 때문..
예시
# SERVER
#!/usr/bin/env python
import time
import rospy
from std_srvs.srv import SetBool, SetBoolResponse
def handle_set_bool(req):
if req.data:
rospy.loginfo("Received a request to set the value to True.")
else:
rospy.loginfo("Received a request to set the value to False.")
# Create a response
response = SetBoolResponse()
response.success = True
response.message = "Value set successfully."
time.sleep(10) # 10초 뒤 RES 보냄
return response
def service_server():
rospy.init_node('service_server')
rospy.Service('set_bool', SetBool, handle_set_bool)
rospy.loginfo("Service server ready.")
time.sleep(9999999)
# rospy.spin() # SPIN 안돌리고 그냥 BLOCKING 만 하면 됨.
if __name__ == '__main__':
service_server()
# CLIENT
#!/usr/bin/env python
import rospy
from std_srvs.srv import SetBool, SetBoolRequest
def service_client(value):
rospy.wait_for_service('set_bool')
try:
set_bool = rospy.ServiceProxy('set_bool', SetBool)
request = SetBoolRequest()
request.data = value
response = set_bool(request)
rospy.loginfo("Service response: %s", response.message)
except rospy.ServiceException as e:
rospy.logerr("Service call failed: %s", e)
if __name__ == '__main__':
rospy.init_node('service_client')
# Call the service with the desired value
service_client(True)
결과
ROS2
결론 :
[ ROS2 는 노드를 spin 돌려야 , future 객체에 data를 기입 및 종료시킬 수 있다. -> future 객체를 다뤄야 server든 client든 callback 함수가 동작을 함. ]
client 쪽에서는 spin 으로 블럭 당하고, req보내고 res 올때까지 또 블럭당한다.
service의 client 는 call_async 후
spin 돌려야 한다.
SERVER 쪽
- "self.srv = self.create_service(AddTwoInts, 'add_two_ints', self.add_two_ints_callback)"
self.add_two_ints_callback <- 콜백이 안돌아가니 동작 전혀 안됌
CLIENT 쪽
- client.py 내부적으로 "sequence_number = _rclpy.rclpy_send_request(capsule, request)"를 하므로
request를 보내긴 하나 callback이 동작안해서 response를 받지 못함
이유 :
client.call_async(req) 로 생성된 future 하나의 객체를 1. main프로그램 2. client.py 3. rclpy(spin하는 주체) 에서 바라보고 관리하는 개념
main 프로그램 에서 리퀘스트 put [ client.call_async(req) ]
1. rclpy : spin 온
2. client.py : req 보내고
3. client.py : future객체를 내부 멤버변수에 등록
4. client.py : 콜백등록 후, future 종료를 기다림.
5. rclpy : future객체에 data 기입 및 종료 <- future.done() 함수가 True 가 되는 시점
6. client.py : 멤버변수에서 삭제(add_done_callback이용)
main 프로그램 에서 future.done()시, 레스폰스 get [ future.result() ]
# SERVER
import time
import rclpy
from rclpy.node import Node
from example_interfaces.srv import AddTwoInts
class MyServer(Node):
def __init__(self):
super().__init__('my_server')
self.srv = self.create_service(AddTwoInts, 'add_two_ints', self.add_two_ints_callback)
def add_two_ints_callback(self, request, response):
response.sum = request.a + request.b
self.get_logger().info('Received request: {0} + {1}'.format(request.a, request.b))
self.get_logger().info('Sending response: {0}'.format(response.sum))
return response
def main(args=None):
rclpy.init(args=args)
server = MyServer()
rclpy.spin(server)
rclpy.shutdown()
if __name__ == '__main__':
main()
import contextvars
import functools
import threading
import time
import asyncio
import rclpy
from rclpy.node import Node
from example_interfaces.srv import AddTwoInts
class SimClient:
def __init__(self):
self.node:Node
def spin_thread(self):
rclpy.spin(self.node)
print(f"rclpy.spin 스핀 종료 !")
def spin_thread_until__future_complete(self, p_node, p_future):
rclpy.spin_until_future_complete(p_node,p_future)
print(f"rclpy.spin_until_future_complete 스핀 종료 ! ")
def main(self, args=None):
rclpy.init(args=args)
self.node = rclpy.create_node('my_client')
client = self.node.create_client(AddTwoInts, 'add_two_ints')
while not client.wait_for_service(timeout_sec=1.0):
self.node.get_logger().info('Service not available, waiting...')
request = AddTwoInts.Request()
request.a = 5
request.b = 3
# # todo 방법 1 -> while 문 루프 돌려서 response받으면(future.done()) break
# future = client.call_async(request)
# while rclpy.ok():
# rclpy.spin_once(self.node)
# if future.done():
# response = future.result()
# self.node.get_logger().info('Received response: {0}'.format(response.sum))
# break
# # 평균 걸린 시간 0.00009 98997688293457
# # todo 방법 2 -> response받으면(future.done()) spin을 종료(set)시키는 함수를 사용
# future = client.call_async(request)
# rclpy.spin_until_future_complete(self.node, future) # future.done() 까지 block
# response = future.result()
# self.node.get_logger().info('Received response: {0}'.format(response.sum))
# # 평균 걸린 시간 0.00010 448217391967774
# # todo 방법 3 -> rclpy에서 제공하는 MultiThreadedExecutor로 SPIN 돌림
# # rclpy.spin를 돌리고 서비스 call 시킴
# spin_thread = threading.Thread(target=self.spin_thread)
# spin_thread.start()
# future = client.call_async(request)
# while rclpy.ok():
# if future.done(): # rclpy.spin() 을 돌리는 상황이면 done() 체킹을 꼭 해줘야함. 왜냐면 done() 상황이 아닌 future는 "future.result()"값을 None 으로 뱉어냄.
# try:
# response = future.result()
# except Exception as e:
# print('Service call failed %r' % (e,))
# else:
# print('Result of add_two_ints: %d' % (response.sum,))
# break
# # 평균 걸린 시간 0.00290 2541160583496
# # todo 방법 4 -> 기본 threading으로 SPIN 돌림
# # call 시키고 future를 받아 종료시 까지 rclpy.spin_until_future_complete 돌림
# future = client.call_async(request)
#
# spin_thread = threading.Thread(target=self.spin_thread_until__future_complete, args=(self.node, future))
# spin_thread.start()
#
# while rclpy.ok():
# if future.done(): # rclpy.spin() 을 돌리는 상황이면 done() 체킹을 꼭 해줘야함. 왜냐면 done() 상황이 아닌 future는 "future.result()"값을 None 으로 뱉어냄.
# try:
# response = future.result()
# except Exception as e:
# print('Service call failed %r' % (e,))
# else:
# print('Result of add_two_ints: %d' % (response.sum,))
# break
# # 평균 걸린 시간 0.00015 689849853515626
# todo 방법 5 -> rclpy에서 제공하는 MultiThreadedExecutor로 SPIN 돌림
# call 시키고 future를 받아 종료시 까지 rclpy.spin_until_future_complete 돌림
# 추가로 future객체 done()이 3초안에 끝나지 않으면 ERROR 로그후 종료
_executor = rclpy.executors.MultiThreadedExecutor()
_executor.add_node(self.node)
future = client.call_async(request)
_executor_thread = threading.Thread(target=_executor.spin_until_future_complete, args=(future,))
_executor_thread.start()
limit=1.0
time_out=time.time() + limit
while rclpy.ok():
if time.time() > time_out:
print(f"{limit}초 동안 response 가 없으므로 타임아웃 ")
break
if future.done(): # rclpy.spin() 을 돌리는 상황이면 done() 체킹을 꼭 해줘야함. 왜냐면 done() 상황이 아닌 future는 "future.result()"값을 None 으로 뱉어냄.
try:
response = future.result()
except Exception as e:
print('Service call failed %r' % (e,))
else:
print('Result of add_two_ints: %d' % (response.sum,))
break
self.node.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
aa=SimClient()
aa.main()
# T=100
# for _ in range(0,T):
# __past = time.time()
# aa.main()
# used_time = time.time() - __past
# ave=used_time/T
# print(f'평균 걸린 시간 {ave}') # <- 같은 Service 네임이라 등록 타이밍이 겹치면 wait 가 좀 걸림
'ros2_python > Ros2 msg,srv,action,parm' 카테고리의 다른 글
ROS2_Action simple example code (0) | 2023.07.03 |
---|---|
ROS2 service blocking 피하는 방법 (0) | 2023.07.01 |
Ros2 비동기적으로 spin( ) (0) | 2022.09.15 |
spin_until_future_complete 예제 (0) | 2022.09.15 |
Ros2 Node 클래스 설명 // 노드랑 sub or pub config 값 바인딩 할때 (0) | 2022.09.07 |
댓글