ABOUT ME

-

Today
-
Yesterday
-
Total
-
  • _ROS1_node_communication
    ROS/ROS1 2023. 10. 4. 16:58

    ROS노드들이 통신을하며 데이터를 주고 받는다.

    이번에는 teacher.py와 student.py를 만들어서 데이터를 주고 받는 예제를 한번 해보도록하자.

     

    1. 패키지 만들기

    $ cd catkin_ws/src # 작업 디렉토리로 이동
    $ catkin_create_pkg msg_send std_msgs rospy # 패키지 이름 설정 및 종속 패키지 추가
    $ cd msg_send # msg_send 폴더로 이동
    & mkdir launch # launch 폴더 생성

    launc 폴더까지 생성을 했으면 catkin_ws로 이동하여 catkin_make를 진행한다.

    이후 teacher.py와 student.py를 생성한다.

    # msg_send로 이동
    $ roscd msg_send
    $ cd src

    teacher.py

    #!/usr/bin/env python
    
    import rospy
    from std_msgs.msg import String
    
    rospy.init_node('teacher')
    pub = rospy.Publisher('my_topic', String)
    rate = rospy.Rate(2)
    
    while not rospy.is_shutdown():
        pub.publish('call me please')
        rate.sleep()

    student.py

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

     

    주의!!: Python으로 만든 코드들은 항상 chmod +x로 실행권한을 줘야한다.

    이제 src폴더에서 launch폴더로 이동하여 msg_send.launch를 만들어보자.

    $ cd .. # 현재 위치인 src의 상위 폴더로 이동
    $ cd launch

    msg_send.launch

    <launch>
        <node pkg="msg_send" type="teacher.py" name="teacher"/>
        <node pkg="msg_send" type="student.py" name="student" output="screen"/>
    </launch>

     

    이제 명령어를 입력하여 msg_send.launch를 실행해보자.

    $ roslaunch msg_send msg_send.launch

    다음과 같이 call me please라고 나오는 것을 볼 수 있다.

     

    2. 여러가지 방법의 통신

    ROS는 다음과 같은 통신을 할 수 있다.

    1:1 통신
    1:N 통신
    N:N 통신

    이번에는 이 통신들이 잘 작동하는지 확인을 해볼 것이다.

    이번에는 값으로 count를 해볼 것이므로 int32 타입의 변수를 사용할 것이다.

    msg_send 패키지의 src 폴더에 teacher_int.py와 student_int.py를 만들자.

     

    teacher_int.py

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

    student_int.py

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

     

    실행할 launch 파일도 다음과 같이 작성해준다.

    1_N.launch

    <launch>
        <node pkg="msg_send" type="teacher_int.py" name="teacher1"/>
        <node pkg="msg_send" type="student_int.py" name="student1" output="screen"/>
        <node pkg="msg_send" type="student_int.py" name="student2" output="screen"/>
        <node pkg="msg_send" type="student_int.py" name="student3" output="screen"/>
    </launch>

    결과:

     

    N_1.launch

    <launch>
        <node pkg="msg_send" type="teacher_int.py" name="teacher1"/>
        <node pkg="msg_send" type="teacher_int.py" name="teacher2"/>
        <node pkg="msg_send" type="teacher_int.py" name="teacher3"/>
        <node pkg="msg_send" type="student_int.py" name="student1" output="screen"/>
    </launch>

    결과:

     

    N_N.launch

    <launch>
        <node pkg="msg_send" type="teacher_int.py" name="teacher1"/>
        <node pkg="msg_send" type="teacher_int.py" name="teacher2"/>
        <node pkg="msg_send" type="teacher_int.py" name="teacher3"/>
        <node pkg="msg_send" type="student_int.py" name="student1" output="screen"/>
        <node pkg="msg_send" type="student_int.py" name="student2" output="screen"/>
        <node pkg="msg_send" type="student_int.py" name="student3" output="screen"/>
    </launch>

    결과:

    모두 값 1이 누락됨을 볼 수 있다.

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

    _ROS1_노드 실습(1)  (0) 2023.10.17
    _ROS1_custom_msg  (0) 2023.10.04
    _ROS1_roslaunch  (0) 2023.10.03
    _ROS1_package_pub&sub  (0) 2023.10.02
    _ROS1_설치_환경설정_기본실습  (0) 2023.10.01
Designed by Tistory.