이제 이루가 사용할 데이터 세트 클래스가 마들어 졌으니, 서버와 클라이언트 코딩을 해보겠다.
프로젝트폴더/src/myServer.py
#!/usr/bin/python3
import rospy
import actionlib
# actionlib 초기화를 위해 CountNumbersAction 클래스를 임포트 하고,
# 그리고, 결과와 피드백 클래스를 임포트 한다
from my_work_action.msg import CountNumbersAction, CountNumbersResult, CountNumbersFeedback
import time # sleep을 위해 임포트
# 클라이언트 호출이 있을때 수행할 함수
def cbServer(goal):
targetNumber = goal.targetNumber # 목표설정!
count = 0
while True:
# feedback 할 값 정의
feedback = CountNumbersFeedback()
feedback.ongoingNumber = count
# feedback 전달!
server.publish_feedback(feedback)
# 1초 쉬었다가 다음 루프로!
time.sleep(1)
# 목표 숫자가 나오면 루프 아웃!
if count == targetNumber:
break
count += 1
# 결과값(result) 정의
result = CountNumbersResult()
result.resultMessage ="Couting Number till {} is finished successfully".format(targetNumber)
# 결과값 전달!
server.set_succeeded(result,"Done!")
# 노드 초기화
rospy.init_node("ActionServer_node")
# 서버 On!
server = actionlib.SimpleActionServer("NumCounting", CountNumbersAction, cbServer, False)
# 서버 Start!
server.start()
# 기다림!!
rospy.spin()
프로젝트폴더/src/myClient.py
#!/usr/bin/python3
import rospy
import actionlib
from my_work_action.msg import CountNumbersAction, CountNumbersGoal
# 서버에서 feedback 값을 전달받으면 수행할 함수
def cbClient(feedback):
print("[Feedback]{}".format(feedback.ongoingNumber))
# 노드 초기화
rospy.init_node('ActionClient_node')
# Client 초기화
client = actionlib.SimpleActionClient("NumCounting", CountNumbersAction)
# 찾는 서버가 On 될때 까지 대기
client.wait_for_server()
# 목표값(Goal) 초기화
goal = CountNumbersGoal()
goal.targetNumber=8 # 전달할 값은 8!
# 목표값 전달!
client.send_goal(goal, feedback_cb=cbClient)
# 결과값 대기
client.wait_for_result()
# 결과값을 받으면 수행할 코드
print("[Result] State: {}".format(client.get_state())) #client 객체 기본제공 메서드
print("[Result] Status: {}".format(client.get_goal_status_text())) #client 객체 기본제공 메서드
print("[Result] message from server: {}".format(client.get_result().resultMessage))
roscore를 실행하고, myserver.py를 실행하고, myclient.py를 실행하면 다음과 같은 결과를 확인할 수 있다.
$ rosrun my_work_action myClient.py
[Feedback]0
[Feedback]1
[Feedback]2
[Feedback]3
[Feedback]4
[Feedback]5
[Feedback]6
[Feedback]7
[Feedback]8
[Result] State: 3
[Result] Status: Done!
[Result] message from server: Couting Number till 8 is finished successfully
$
'ROS' 카테고리의 다른 글
ROS1-13 액션 예제 3 - 서버 동작 (0) | 2022.07.28 |
---|---|
ROS1-12 액션 예제 1 - 준비하기 (0) | 2022.07.28 |
ROS1-11 서비스 예제 - 서비스 코드 (0) | 2022.07.27 |
ROS1-10 서비스 예제 - 서비스 메시지 준비하기 (0) | 2022.07.27 |
ROS1-09 토픽 예제2 - 사용자가 정의한 자료형 (0) | 2022.07.26 |