ABOUT ME

-

Today
-
Yesterday
-
Total
-
  • _ROS1_노드 실습(1)
    ROS/ROS1 2023. 10. 17. 15:46

    이번에는 노드간 통신을 하며 발생하는 문제들과 해결 방안을 살펴보려고 한다.

    1. 노드간 동기화 문제

    우리가 노드로 통신을 주고받을 때 누락없이 잘 도착하는지를 보려고 한다.

    해당 예제를 보기 위해 sender, receiver를 사용하려고 한다.

    - Python

    - sender.py

    #!/usr/bin/env python
    
    import rospy
    from std_msgs.msg import Int32
    
    rospy.init_node('sender_serial')
    pub = rospy.Publisher('my_topic', Int32, queue_size(2))
    rate = rospy.Rate(2)
    count = 1
    
    while not rospy.is_shutdown():
        pub.publish(count)
        count = count + 1
        rate.sleep()

    - receiver.py

    #!/usr/bin/env python
    
    import rospy
    from std_msgs.msg import Int32
    
    def callback(msg):
        print msg.data
    
    rospy.init_node('receiver_serial')
    sub = rospy.Subscriber('my_topic', Int32, callback)
    rospy.spin()

     

    - C++

    - sender.cpp

    #include "ros/ros.h"
    #include "std_msgs/Int32.h"
    
    int main(int argc, char **argv){
        ros::init(argc, argv, "sender");
        ros::NodeHandle n;
        ros::Publisher chatter_pub = n.advertise<std_msgs::Int32>("my_topic", 1000);
        ros::Rate loop_rate(10);
        int count = 1;
    
        while(ros::ok()){
            std_msgs::Int32 msg;
            msg.data = count;
            ROS_INFO("%d", msg.data);
            chatter_pub.publish(msg);
            ros::spinOnce();
            loop_rate.sleep();
            ++count;
        }
        return 0;
    }

    - receiver.cpp

    #include "ros/ros.h"
    #include "std_msgs/Int32.h"
    
    void my_topic_Callback(const std_msgs::Int32::ConstPtr& msg)
    {
    	ROS_INFO("I received: [%d]", msg -> data);
    }
    
    int main(int argc, char **argv)
    {
    	ros::init(argc, argv, "receiver");
    	ros::NodeHandle n;
    	ros::Subscriber sub = n.subscribe("my_topic", 1000, my_topic_Callback);
    	ros::spin();
    
    	return 0;
    }

     

     

    데이터를 받는 receiver를 먼저 실행하고, sender를 실행하여 데이터가 누락되는지 확인을 해본다.

    결과를 보면 값이 누락됨을 확인할 수 있다.

     

    Python 결과
    C++ 결과

    해결방안

    이를 해결하기 위해서는 receiver노드가 토픽을 수신할 수 있을때 sender가 메시지를 전송하면 된다.

    - Python

    - sender.py

    #!/usr/bin/env python
    
    import rospy
    from std_msgs.msg import Int32
    
    rospy.init_node('sender_serial')
    pub = rospy.Publisher('my_topic', Int32, queue_size = 2)
    rate = rospy.Rate(2)
    
    ## receiver 노드가 토픽을 수신할 수 있을 때까지 기다림.
    while(pub.get_num_connections() == 0):
        count = 1
    
    while not rospy.is_shutdown():
        pub.publish(count)
        count = count + 1
        rate.sleep()

     

    - C++

    - sender.cpp

    #include "ros/ros.h"
    #include "std_msgs/Int32.h"
    
    int main(int argc, char **argv){
        ros::init(argc, argv, "sender");
        ros::NodeHandle n;
        ros::Publisher chatter_pub = n.advertise<std_msgs::Int32>("my_topic", 1000);
        ros::Rate loop_rate(10);
        int count = 1;
    
        // receiver 노드가 토픽을 수신할 수 있을 때까지 대기
        while(chatter_pub.getNumSubscribers() == 0){    }
    
        while(ros::ok()){
            std_msgs::Int32 msg;
            msg.data = count;
            ROS_INFO("%d", msg.data);
            chatter_pub.publish(msg);
            ros::spinOnce();
            loop_rate.sleep();
            ++count;
        }
        return 0;
    }

     

    누락없이 결과를 받는것을 볼 수 있다.

    Python 결과
    C++ 결과

    1:N통신

    1개의 receiver와 3개의 sender에서도 데이터가 누락되지 않음을 볼 수 있다.

    sender.launch

    <launch>
        <include file="$(find sender_test1/launch/sender.launch)"/>
        <include file="$(find sender_test2/launch/sender1.launch)"/>
        <include file="$(find sender_test3/launch/sender2.launch)"/>
    </launch>

    결과

     


    2. ROS 처리 지연 문제

    만약, topic으로 너무나도 많은 데이터를 보내서 받는 부분에서 도착하는 데이터를 모두 처리할 수 없는 경우 어떻게 되는가?

    - Python

    - sender_overflow.py

    #!/usr/bin/env python
    
    import rospy
    from std_msgs.msg import Int32
    
    name = "sender"
    pub_topic = "my_topic"
    
    rospy.init_node(name)
    pub = rospy.Publisher(pub_topic, Int32, queue_size=1)
    
    rate = rospy.Rate(1000)
    count = 0
    
    while(pub.get_num_connections() == 0):
        continue
    
    while not rospy.is_shutdown():
        pub.publish(count)
        count = count + 1
        rate.sleep()

     

    - receiver_overflow.py

    #!/usr/bin/env python
    
    import rospy
    from std_msgs.msg import Int32
    
    name = "receiver"
    sub_topic = "my_topic"
    
    def callback(msg):
        rospy.loginfo("callback is beging processed")
        rospy.sleep(5)
        print msg.data
    
    rospy.init_node(name)
    rospy.Subscriber(sub_topic, Int32, callback, queue_size=1)
    rospy.spin()

     

    - sr_overflow.launch

    <launch>
        <node pkg="node_overflow" type="receiver_overflow.py" name="receiver" output="screen"/>
        <node pkg="node_overflow" type="sender_overflow.py" name="sender"/>
    </launch>

     

    - C++

    - sender_overflow.cpp

    #include "ros/ros.h"
    #include "std_msgs/Int32.h"
    
    int main(int argc, char **argv){
        ros::init(argc, argv, "sender");
        ros::NodeHandle n;
        ros::Publisher over_sender = n.advertise<std_msgs::Int32>("my_topic", 1);
        ros::Rate loop_rate(1000);
        int count = 1;
    
        while(over_sender.getNumSubscribers() == 0){}
    
        while(ros::ok()){
            std_msgs::Int32 msg;
            msg.data = count;
            ROS_INFO("%d", msg.data);
            over_sender.publish(msg);
            ros::spinOnce();
            loop_rate.sleep();
            ++count;
        }
    }

     

    - receiver_overflow.cpp

    #include "ros/ros.h"
    #include "std_msgs/Int32.h"
    
    void my_topic_Callback(const std_msgs::Int32::ConstPtr& msg)
    {
    	ROS_INFO("callback is being processed: %d", msg -> data);
    }
    
    int main(int argc, char **argv)
    {
    	ros::init(argc, argv, "receiver");
    	ros::NodeHandle n;
    	ros::Subscriber sub = n.subscribe("my_topic", 1, my_topic_Callback);
    	ros::spin();
    
    	return 0;
    }

     

    하지만 C++은 속도가 빨라서 누락이 잘 발생하지 않는 것 같다.

     

    결과를 보면 받은 토픽이 1씩 증가하지 않고 중간에 잃어버리는 것을 볼 수 있다.

    Python: queue_size = 1

    이는 받는 부분인 receiver_overflow의 queue_size를 늘리면 된다.

    아래는 queue_size를 10000으로 늘린 결과이다.

    Python: queue_size = 10000

    느리지만 꾸준히 받아오는 것을 확인할 수 있었다.

    'ROS > ROS1' 카테고리의 다른 글

    _ROS1_rviz  (1) 2023.10.23
    _ROS1_노드 실습(2)  (1) 2023.10.17
    _ROS1_custom_msg  (0) 2023.10.04
    _ROS1_node_communication  (0) 2023.10.04
    _ROS1_roslaunch  (0) 2023.10.03
Designed by Tistory.