-
_ROS1_노드 실습(2)ROS/ROS1 2023. 10. 17. 19:34
1. 타임 슬롯
만약 데이터를 주기적으로 발송하다가 타임슬롯을 오버하면 어떻게 될까??
주로 rospy.Rate()와 rospy.sleep()으로 이 주기를 조절하는데 이를 그림으로 표현하면 다음과 같이 볼 수 있다.
Rate(5)는 1초에 하는 일의 양을 이야기하며 0.2초씩 1번 일을 수행한다.
rate.sleep()은 0.2초안에 일을 하고 남은 시간은 쉰다는 의미이다.
이번에는 일을 수행하는 양이 많아져서 0.2초를 넘는다면 어떻게 되는지 보자.
- Python
- sender_job.py
#!/usr/bin/env python import rospy import time from std_msgs.msg import Int32 def do_job(count): for i in range(0, count): i = i + 1 pub.publish(i) def list_append_time(): start.append(start_time) end.append(end_time) sleep.append(sleep_time) name = "sender_job" pub_topic = "my_topic" rospy.init_node(name) pub = rospy.Publisher(pub_topic, Int32, queue_size=0) rate = rospy.Rate(5) while not rospy.is_shutdown(): start = [] end = [] sleep = [] num = input("input count number: ") rate.sleep() total_start = time.time() for j in range(0, 5): start_time = time.time() do_job(num) end_time = time.time() rate.sleep() sleep_time = time.time() list_append_time() total_end = time.time() for t in range(0, 5): sleep[t] = sleep[t] - end[t] end[t] = end[t] - start[t] for result in range(0, 5): print("speed time > ", round(end[result], 4), 's') print("sleep time > ", round(sleep[result], 4), 's') print("-------------------------") print("total_time > ", round(total_end - total_start, 4), 's') print("-------------------------\n\n")
결과는 컴퓨터 성능에 따라 다르다.
Python에서 count를 1000으로 하면 1초에 다음 시간동안 작업이 발생함을 볼 수 있다.
count를 점점 늘리면 다음과 같이 된다. (1초를 넘어가는 것을 볼 수 있다.)
2. 노드의 순차 실행
협업해야하는 노드들을 순서대로 기동할 수 있을까?
예를들어 receiver node가 1번, 2번, 3번 노드들을 순서대로 받는다면 어떻게 해야할까?
이는 receiver node가 topic을 보내라는 사인을 주기 전까지, 각 노드들을 기다리게 하면 된다.
- Python
- receiver.py
#!/usr/bin/env python import rospy from std_msgs.msg import String name = "receiver" pub_topic = "start_ctl" sub_topic = "msg_to_receiver" def callback(data): rospy.loginfo("I heard %s", data.data) rospy.init_node(name) rospy.Subscriber(sub_topic, String, callback) pub = rospy.Publisher(pub_topic, String, queue_size=1) rate = rospy.Rate(10) hello_str = String() rospy.sleep(1) sq = ["first", "second", "third", "fourth"] pub_msg = String() for i in sq: pub_msg.data = i+":go" pub.publish(pub_msg) rospy.sleep(3) rospy.spin()
- first.py ~ fourth.py
#!/usr/bin/env python import rospy from std_msgs.msg import String name = "first" # 이부분만 second ~ fourth까지 작성 pub_topic = "msg_to_receiver" sub_topic = "start_ctl" OK = None def ctl_callback(data): global OK OK = str(data.data) rospy.init_node(name) rospy.Subscriber(sub_topic, String, ctl_callback) while True: if OK == None: continue d = OK.split(":") if(len(d) == 2) and (d[0] == name) and (d[1] == "go"): break pub = rospy.Publisher(pub_topic, String, queue_size=1) rate = rospy.Rate(2) hello_str = String() while not rospy.is_shutdown(): hello_str.data = "my name is " + name pub.publish(hello_str) rate.sleep()
- sr_order.launch
<launch> <node name="receiver" pkg="node_order" type="receiver.py" output="screen"/> <node name="first" pkg="node_order" type="first.py" output="screen"/> <node name="second" pkg="node_order" type="second.py" output="screen"/> <node name="third" pkg="node_order" type="third.py" output="screen"/> <node name="fourth" pkg="node_order" type="fourth.py" output="screen"/> </launch>
결과를 보면 다음과 같다.
first부터 순차적으로 실행되는 것을 볼 수 있다.
3. 받은 토픽 가공
ROS를 사용하면 노드로부터 토픽을 받고 해당 데이터를 가공해서 다른 노드로 보내는 경우가 많다.
이번에는 이를 실습해보려고 한다.
- custom_msg
이전에 사용한 custom_msg를 사용할 것이다.
string last_name int32 age int32 score string phone_num int32 id_number
- Python
- receiver.py
#!/usr/bin/env python import rospy from msg_send.msg import my_msg from std_msgs.msg import String import time def callback(data): st_name = data.last_name + '' + data.first_name curr_time = time.strftime('%Y-%m-%d %H:%M:%S', time.localtime()) st_name2 = 'Good morning, ' + st_name + '' + curr_time pub.publish(st_name2) rospy.init_node('remote_receiver', anonymous=True) pub = rospy.Publisher('msg_from_receiver', String, queue_size=1) sub = rospy.Subscriber('msg_to_sender', my_msg, callback) rospy.spin()
- sender.py
#!/usr/bin/env python import rospy from msg_send.msg import my_msg from std_msgs.msg import String done = False def callback(data): print(data.data) done = True rospy.init_node('remote_sender', anonymous=True) pub = rospy.Publisher('msg_to_sender', my_msg, queue_size=1) rospy.Subscriber('msg_from_receiver', String, callback) rate = rospy.Rate(1) msg = my_msg() msg.first_name = "woo" msg.last_name = "Mokchanic_" msg.age = 29 msg.score = 999 msg.id_number = 876321 msg.phone_num = "010-9933-0022" while not rospy.is_shutdown() and not done: pub.publish(msg) print("sending msg..") rate.sleep()
결과는 다음과 같다.
'ROS > ROS1' 카테고리의 다른 글
_ROS1_sensors & IMU (0) 2023.10.24 _ROS1_rviz (1) 2023.10.23 _ROS1_노드 실습(1) (0) 2023.10.17 _ROS1_custom_msg (0) 2023.10.04 _ROS1_node_communication (0) 2023.10.04