<Noetic과 Melodic>
제일 마음에 걸리는 부분은
내가 작업한 ros version은 noetic 인데
기존 노트북에 깔려있는 버전은 melodic 이라는 점이다
이에 대해 공식문서에서
https://discourse.ros.org/t/ros-cross-distribution-communication/27335
ROS Cross-Distribution Communication
Just out of curiosity, I happened to check ROS cross-distribution communication. Topic and Services are confirmed using latest container with host network. ROS 1 Scenario ROS Master Can communicate? kinetic/melodic kinetic YES melodic/noetic kinetic YES no
discourse.ros.org
가능하다고 하니 한번 하고 나중에 그냥 noetic으로 통일하는 방향으로 바꾸자
<Publisher - 노트북>
제일 먼저 노트북에 workspace를 새로 만들어주자
기존에 workspace를 만들고 돌렸던 적이 있기 때문에 먼저 bashrc를 바꿔주자
sudo nano ~/.bashrc
주석을 먼저 달아주고 기존에 쓰던 workspace (turtlebot)을 주석처리 해준다
그 다음 workspace를 만들어 준다
mkdir -p catkin_ws1/src
cd catkin_ws1/src
그 다음 패키지를 만들어주자
catkin_create_pkg height_pkg rospy std_msgs
cd height_pkg
그 다음 소스코드를 옮겨 주자
nano height_publish_example.py
#!/usr/bin/env python3
import rospy
from std_msgs.msg import Float32
from random import randint
def height_publisher():
pub = rospy.Publisher('height', Float32, queue_size=10)
rospy.init_node('height_publisher', anonymous=True)
rate = rospy.Rate(0.5)
while not rospy.is_shutdown():
rand_height = randint(70,200)
hello_str = str(rand_height)+"%s" % rospy.get_time()
rospy.loginfo(hello_str)
pub.publish(rand_height)
rate.sleep()
if __name__ == '__main__':
try:
height_publisher()
except rospy.ROSInterruptException:
pass
혹시 몰라서 한글 주석은 전부 제거했다
그 다음 소스코드에 실행 권한을 주고
chmod +x height_publish_example.py
CMakeLists에 아래의 코드를 추가하자 (이건 cpp인 경우에만 수정하고 지금은 python이기 때문에 생략한다)
cd ../
nano CMakeLists.txt
## Your package locations should be listed before other locations
include_directories(
# include
${catkin_INCLUDE_DIRS}
)
add_executable(height_publish_node src/height_publish_example.py)
target_link_libraries(height_publish_node ${catkin_LIBRARIES})
그 다음 workspace 디렉토리로 이동하여서 컴파일을 진행하자
cd ../../
catkin_make
export ROS_PACKAGE_PATH=~/catkin_ws`/src:/opt/ros/melodic/share
그 다음 본인의 ip와 gateway를 확인해주자
ifconfig
route
이제 실행시켜보자
nano ~/.bashrc
먼저 bashrc에 다음 문장을 추가하고
source ~/catkin_ws1/devel/setup.bash
기왕 연김에
ros경로도 확인해주면 좋긴하다
추가로 이제 IP를 건드려 줘야하는데
내가 원하는 것은 subsriber 쪽에 master 가 있었으면 하기 때문에
subscriber를 적어줄 데스크탑의 IP를 Master_URI로 적어주자
HostName 은 위에서 확인했던 노트북의 ip를 적어줬다
source /opt/ros/melodic/setup.bash
source ~/catkin_ws1/devel/setup.bash
export ROS_PACKAGE_PATH=~/catkin_ws1/src:/opt/ros/melodic/share
export ROS_MASTER_URI=http://192.168.1.83:11311
export ROS_HOSTNAME=192.168.1.95
위에 사항들을 변경/추가 해준 다음에
변경사항을 저장해준 다음
source ~/.bashrc
<실행화면>
Master URI 가 내 데스크탑으로 지정이 되어있기 때문에
데스크탑에서 roscore를 돌려줘야 한다 Master 가 서버역할을 하므로 roscore를 돌려야한다
roscore
실행 시켜보면
rosrun height_pkg height_publish_example.py
사실 위에 코드를 보면 알 수 있지만 실행 터미널창에서는 그렇게 드라마틱한 정보를 얻을 수는 없다
왜냐하면 그냥 실행 유무를 확인하고자 짠 코드이기 때문이기도 하고 지금 이 실행화면은 publish가 잘 되고 있는지는
감지하지 못하기 때문에 (Publish 부분이 오류가 있어도 돌아감)
다음 명령어로 살펴보자
먼저 어떤 topic들이 날라가고 있는지 확인을 하고자 아래의 명령어를 실행한다 (돌려놓은 상태로 새 터미널에서)
rostopic list
다음과 같이 지정한 height가 잘 날라가고 있고
좀 더 자세한 정보를 보기 위해
rostopic info /height
Float 데이터 타입으로 현재 subscriber 코드는 돌리지 않았으므로 없고
Publisher는 고정된 노트북의 IP 192.168.1.95 가 잘 설정되어 있는 것을 볼 수 있다
<Subscriber - 데스크탑>
다음으로 데스크탑을 세팅해주는데 사실 데스크탑으로 아래의 포스팅
를 작성하면서 이미 설정이 되어 있지만
과정을 작성한다면
mkdir -p catkin_ws3/src
cd catkin_ws3/src
catkin_create_pkg height_pkg3 rospy std_msgs
cd height_pkg3
nano height_subscribe_example.py
#!/usr/bin/env python3
#-*- coding:utf-8 -*- # 한글 주석을 달기 위해 사용한다.
import rospy
from std_msgs.msg import Float32
data = None #전역변수로 선언을 해주고
def callbackFunction(msg): #기본 argument는 구독한 메세지 객체
#callback : topic이 발행되는 이벤트가 발생하였을 때 event lisner함수를 콜백함수로 요구
global data
data = msg
rospy.loginfo(data)
def height_subscriber():
subscriber = rospy.Subscriber(
name="height", data_class=Float32, callback=callbackFunction)
rospy.init_node("height_subscriber")
rate = rospy.Rate(0.5) # 1000hz
while not rospy.is_shutdown(): #-> c++에서 ros.ok() 느낌
rospy.loginfo(rospy.get_time())
rate.sleep() #100hz가 될때 까지 쉬기
if __name__ == '__main__':
try:
height_subscriber()
except rospy.ROSInterruptException:
pass
chmod +x height_publish_example.py
cd ../
nano CMakeLists.txt
cd ../../
catkin_make
nano ~/.bashrc
다음을 추가해주자
export ROS_PACKAGE_PATH=~/catkin_ws3/src:/opt/ros/noetic/share
#set ROS noetic
source /opt/ros/noetic/setup.bash
source ~/catkin_ws3/devel/setup.bash
# set ROS NETWORK
export ROS_HOSTNAME=192.168.1.83
export ROS_MASTER_URI=http://${ROS_HOSTNAME}:11311
변경사항을 저장해주고
source ~/.bashrc
<실행화면>
실행을 위해 master이므로 roscore를 열어주고
roscore
실행시켜보면
rosrun height_pkg3 height_subscribe_example.py
다음과 같은 화면을 볼 수 있는데
위에 코드를 보면 get_time 뿐만 아니라 data도 있는데 data 가 안 뜨는 상황을 볼 수 있다
이는 Publisher가 안 켜져 있기 때문인데
이제 세팅이 끝났으니 노트북에 있는 파일을 실행 시켜주면
rosrun height_pkg height_publish_example.py
다음과 같은 화면을 얻을 수 있고 이는 topic을 제대로 받고 있다는 뜻이다
마찬가지로 topic를 좀더 살펴보면
rostopic list
/height를 볼 수 있고
rostopic info /height
Publisher는 내 데스크탑 IP인 192.168.1.83 Subscriber는 노트북 IP인 192.168.1.95 인 것을 확인 할 수 있고
<결과>
좀더 가시적으로 보고 싶으면
rqt_graph
height_publisher node에서 height_subsciber node로 height topic이 이동하는 것을 볼 수 있다
그리고 실시간으로 어떤 정보가 오고 가는지를 확인하고 싶으면
rostopic echo /height
<데스크탑>
<노트북>
서로 동일한 정보를 주고 받는 것을 볼 수 있다
'Robotics > Collabot_proj' 카테고리의 다른 글
[Robotics] Collabot 현업(7) [한 node에 subscribe & publish 동시 진행] (0) | 2023.05.02 |
---|---|
[Robotics] Collabot 현업(6) [rosbag을 이용한 개발] (0) | 2023.05.02 |
[Robotics] Collabot 현업(4) [내 PC내 가상환경과 다른 PC 통신] (0) | 2023.04.26 |
[Robotics] Collabot 현업(3) [ROSpy subscriber 만들어 보기] (0) | 2023.04.21 |
[Robotics] Collabot 현업(2) [ROSpy publisher 만들어 보기] (0) | 2023.04.20 |