ROS를 이용한 로봇 프로그래밍을 처음 시작할 때, 그것도 특히 제로 빌드를 하는 것이 아니라 다른 사람이 만들어둔 패키지들을 테스트 할 때, 아마 아래와 비슷한 오류를 많이 보았을 것이라고 생각한다.
TF_OLD_DATA ignoring data from the past for frame left_gripper at time 1415804777
TF_NO_FRAME_ID: Ignoring transform from authority "default_authority" because frame_id not set
이런 오류는 매우 흔하지만, TF에 대한 개념이 잘 잡혀있지 않다면 이를 해결하는 것에 많은 노력이 필요할 것이다. 그런 의미로, 이번 글에서는 TF란 무엇인지에 대하여 서술할 예정이다.
ROS에서 기본적으로 제공해주는 메세지 타입 중, 공간과 관련된 메세지 타입들은 아래와 같은 공통된 헤더를 가지게 된다.
바로 std_msgs/Header인데, 이는 아래와 같이 정의되어 있다.
헤더는 3개의 기본적인 자료형의 필드를 가진다.
이 중에서 오늘 다룰 내용과 깊은 관련이 있는것은 stamp와 frame_id이다.
time은 단순히 해당 메세지가 발행된 시간이라는 의미이고, frame_id는 해당 메시지가 어떤 frame에 속해있는지를 의미한다.
그렇다면 드는 당연한 의문은, frame이란 무엇일까?
그 답은 바로 좌표계의 이름이다.
구체적으로 설명하자면, 모든 ROS의 프레임은 유클리드 좌표계로 구성되어 있는데, 각각의 프레임은 서로 독립된 상태이다. 여기서, frame_id를 통하여 각각의 좌표계를 서로 구분할 수 있게 하는 것이다.
구체적인 예시를 보여주면, 아래는 frame1이라는 이름을 가지는 좌표계에 임의의 좌표값을 가지는 Pose를 발행하는 코드이다. 발행(Publish)에 대하여는 전 글을 참고하면 이해하기 쉬울 것이다.
#!/usr/bin/python
import rospy
import random
import math
from tf.transformations import quaternion_from_euler
from geometry_msgs.msg import PoseStamped
if __name__ == '__main__':
rospy.init_node("tf_test")
pub = rospy.Publisher("pose", PoseStamped, queue_size=1)
r = rospy.Rate(1)
while not rospy.is_shutdown():
msg = PoseStamped()
msg.header.stamp = rospy.Time.now()
msg.header.frame_id = "frame1"
msg.pose.position.x = random.randint(0, 5)
msg.pose.position.y = random.randint(0, 5)
msg.pose.position.z = 0
quat = quaternion_from_euler(
0., 0., math.radians(random.randint(0, 180)))
msg.pose.orientation.x = quat[0]
msg.pose.orientation.y = quat[1]
msg.pose.orientation.z = quat[2]
msg.pose.orientation.w = quat[3]
pub.publish(msg)
r.sleep()
위와 같은 코드를 실행시키고, rviz에 "pose"라는 이름의 토픽을 구독하도록 설정하면 아래와 같이 나타나게 된다.
For frame [frame1]: Fixed Frame [base_link] does not exist
이는 매우 당연한 오류인데, Display의 Global Options를 보면, Fixed Frame이 base_link라는 이름으로 되어있다.
즉, 해당 화면은 base_link 라는 이름을 가지는 좌표계를 보여주고 있는 것인데, pose라는 이름의 토픽은 frame1 이라는 이름을 가지는 좌표계에 존재하는 점이기 때문에, 당연히 출력이 되지 않고, 오류 메세지를 보내는 것이다.
이를 해결하기 위해서, Fixed Frame를 frame1로 바꿔보면...
아까의 오류는 사라지고, 정상적으로 작동하는 것을 확인할 수 있다.
위와 같은 내용을 통하여, ROS 메시지의 헤더에는 frame_id를 정의할 수 있고, frame은 독립된 유클리드 좌표계이며, frame_id라는 값을 이용해 구분할 수 있다는 것을 알았다.
그렇다면 정말 중요한 것은 왜 이렇게 만들어졌을까?
만약, frame이 존재하지 않는 상황을 생각해보자. 어떤 문제점이 존재할까?
예를 들어, 사람을 닮은 휴머노이드가 있다고 가정해보자. 로봇 프로그래밍에서, 가장 중요한 것중 하나는 바로 로봇의 상태(State)을 인식하는 것이다. 그렇다면 해당 로봇이 인식해야 하는 상태는 로봇의 절대적인 위치, 로봇의 오른팔의 위치, 각 손가락의 모양... 등이 존재할 것이다.
그렇다면, 이 로봇의 절대적인 위치는 어떻게 표현할까? 이 로봇의 위치를 표현할 때, 어떤 좌표계를 사용하여 원점을 어디로 잡아서 어떻게 표현할 수 있을까?
아마 절대적인 위치를 표현하기 가장 좋은 방법은 위도와 경도일 것이다. 개발의 편의성을 위해, 위경도를 미터단위로 바꾸어서 표현하였다고 생각해보자.
이런 방법을 사용한다면, 로봇의 각 상태를 하나의 좌표계 상에서 표현할 수는 있지만, 너무 번거롭다는 생각이 들지 않을까 싶다. 로봇의 오른손가락의 간격을 일정하게 펴는 명령을 보내고 싶어도, 현 오른 손가락들의 간격을 확인하려면, 수천만 크기의 거리에서 계산해야 하는 것이다. 오른손가락1의 위치는 (100만, 100만, 0)입니다... 같은 어이없는 상황이 펼쳐지는 것은 그 누구도 원하지 않는다.
여기서 나오는 발상이 바로, 여러개의 좌표계를 두어 계산한다는 발상이다.
로봇의 중심점을 base_link라는 이름으로, 세계의 절대적인 좌표를 world라는 이름으로 잡는다면, 로봇은 base_link 프레임에서는 (0, 0, 0), world 프레임에서는 (37, 127) 같은 식으로 표현할 수 있다.
이런 방식으로, 오른손 좌표계를 right_hand라는 이름으로 한다면, 손가락 1의 위치는 (-5, 5), 2의 위치는 (-3, 3)... 같은 식으로 표현이 가능해지는 것이다.
위와 같은 방법으로, 좌표계를 여러개 설정하면 비교적 간단하게 좌표 문제를 해결할 수 있다는 것을 알았다. 그렇다면, 가장 중요한 것은 각 좌표계끼리 어떤 관계를 가지고 있는가이다. 오른손 좌표계에서 오른손가락들의 위치를, 왼손 좌표계에서 왼손가락을의 위치를 정의하는 것은 가능하지만, 그렇다면 오른손가락과 왼손가락으로 깍지를 끼려면 어떻게 해야할까?
당연히 로봇 중심(base_link)를 기준으로 계산을 해야할 것이다. 하지만 지금까지의 내용으로는 오른손 좌표계의 (-5, 5)가 로봇 중심 좌표계에서는 어느 점에 해당하는지 알 수가 없다.
비슷하게, 로봇이 하나가 아니라 여러대가 존재하고, 이 로봇들을 한 곳으로 집합 시키고 싶다면? 당연히 world 좌표를 기준으로 계산해야할 것이다.
이처럼, 단순하게 좌표계의 숫자를 늘려서 표현하는 것은, 특정 문제는 매우 쉽게 해결할 수 있지만, 이로 인해서 다른 문제점이 발생하게 된다. 따라서 ROS에서 각각의 좌표계끼리의 관계를 정의할 필요가 생기는데, 이를 TF(Transform)라고 한다.
자, 그러면 아래와 같은 내용을 해결해보자.
- world 프레임에서 로봇의 귀환지의 좌표는 (10, 10, 0)이다
- 로봇의 귀환지를 기준으로, 로봇은 현재 (-5, 10, 0) 떨어진 곳에 존재한다
이 때, 로봇의 위치는 world 프레임 기준으로 어디일까?
우선, 로봇의 귀환지를 원점으로 하는 좌표계의 이름을 home이라고 해보자. 그렇다면, home 프레임 상에서 (-5, 10, 0) 만큼 떨어진 위치는 아래와 같이 표현될 것이다.
#!/usr/bin/python
import rospy
import tf
from geometry_msgs.msg import PoseStamped
class Robot(object):
def __init__(self):
position = PoseStamped()
position.header.frame_id = "home"
position.pose.position.x = -5
position.pose.position.y = 10
position.pose.orientation.w = 1
self.position = position
self.pub = rospy.Publisher("robot_pose", PoseStamped, queue_size=1)
def publishPose(self):
self.position.header.stamp = rospy.Time.now()
self.pub.publish(self.position)
if __name__ == '__main__':
rospy.init_node("tf_pub")
robot = Robot()
r = rospy.Rate(1)
while not rospy.is_shutdown():
robot.publishPose()
r.sleep()
자, 그러면 이번에는 home 프레임과 world 프레임 간의 관계를 정의해야 한다. 여기에는 tf.TransformBroadcaster() 클래스와, 해당 클래스에 선언된 sendTransform 메소드를 이용한다.
sendTransform 메소드는 아래와 같은 매개변수를 받아, TF 관계를 발행한다.
translation: Any, rotation: Any, time: Any, child: Any, parent: Any
구체적으로는, translation은 좌표계 간의 병진운동을 정의하는 값으로, 길이 3의 어레이를 요구하며(x, y, z), rotation은 화전운동을 정의하는 값으로, 쿼터니안 좌표로 길이 4의 어레이를 요구한다(x, y, z, w).
time은 해당 관계를 가지는 시점의 time객체를, 그리고 child와 parent는 string 타입으로 부모와 자식 프레임 이름을 요구한다.
여기서 부모와 자식이란, 어떤 프레임을 더 상위의 프레임으로 취급할지를 의미한다.
따라서 위의 내용을 코딩하면 아래와 같다.
tf_broadcaster = tf.TransformBroadcaster()
r = rospy.Rate(1)
while not rospy.is_shutdown():
tf_broadcaster.sendTransform(
translation=[10, 10, 0],
rotation=[0., 0., 0., 1],
time=rospy.Time.now(),
child="home",
parent="world"
)
robot.publishPose()
r.sleep()
객체 선언과 함수 호출만으로 TF 관계를 정의하는 것에 성공했다. 이 결과를 RVIZ에서 확인한다면, 아래와 같다.
Fixed Frame이 world로 되어있지만, world와 home 프레임 간의 관계를 잡아주었기 때문에, world 프레임 상에서 로봇의 위치를 알 수 있게 된 것이다.
또한, 보다싶이 TF 관계의 발행은 ROS Publisher와 매우 유사한 형태를 가지고 있는데, 이와 비슷하게 TF관계 또한, 구독하여 실제 프레임 간의 좌표 변환을 시킬 수 있다.
구체적으로는 tf.TransformListener 클래스를 사용할 수 있다.
사용법은 아래와 같은 코드를 참고하면 된다.
#!/usr/bin/python
import rospy
import tf
from geometry_msgs.msg import PoseStamped
if __name__ == '__main__':
rospy.init_node("tf_listener")
tf_listener = tf.TransformListener() # TF Listener 객체 선언
r = rospy.Rate(1)
while not rospy.is_shutdown():
if tf_listener.canTransform(
target_frame="world", source_frame="home", time=rospy.Time(0)):
# TF 변환이 가능한지 검사. 불가능 할 때, lookupTransform을 호출할 경우 예외 발생
# TF 변환시 시간은 rospy.Time.now()가 아니라 Time(0)을 써야한다!!
tf_matrix = tf_listener.lookupTransform(
target_frame="world", source_frame="home", time=rospy.Time(0))
# 변환 행렬 리턴. 리턴 값은 ([x, y, z], [x, y, z, w])
rospy.loginfo(tf_matrix)
else:
rospy.logwarn("Cannot lookup transform between world and home")
r.sleep()
위의 코드를 실행한 결과는 아래와 같다.
또한, ROS Docs를 참고하면, TransformListener가 사용 가능한 여러 메소드를 확인할 수 있다.
이 중에서 transformPose를 사용한 결과는 아래와 같다.
#!/usr/bin/python
import rospy
import tf
from geometry_msgs.msg import PoseStamped
msg = None
def poseCallback(m):
global msg
m.header.stamp = rospy.Time(0)
msg = m
if __name__ == '__main__':
rospy.init_node("tf_listener")
tf_listener = tf.TransformListener()
pose_subscriber = rospy.Subscriber(
"robot_pose", PoseStamped, callback=poseCallback)
r = rospy.Rate(1)
while not rospy.is_shutdown():
if tf_listener.canTransform(
target_frame="world", source_frame="home", time=rospy.Time(0)) and msg is not None:
res = tf_listener.transformPose(ps=msg, target_frame="world")
rospy.loginfo(res)
else:
rospy.logwarn("Cannot lookup transform between world and home")
r.sleep()
위와 같은 내용을 통하여, Frame과 TF의 의미와 사용법을 알아보았다. 하지만, 혹시 이런 의문이 들지는 않을까. TF는 전혀 새로운 내용이 아니며, 변환 행렬의 계산은 numpy 등 단순 행렬 계산을 통하여 얼마든지 대신할 수 있고, 오히려 그쪽이 빠르지 않을까?
물론 완전히 틀린 말은 아니지만, ROS의 tf 패키지를 사용하면, 시간에 따라 변화하는 변환 행렬을 추적하기 편리하며, 다른 ROS 라이브러리와 연동되어 귀찮은 작업을 대폭 감소시킬 수 있다.
또한, 프레임 간 부모-자식 관계는 단순히 하나만 존재하는 것이 아니라, 트리 구조로 무한하게 확장할 수 있으며, TransformListener를 사용한다면, 여러 좌표계 간의 변환 행렬을 한번에 계산 가능하다는 장점이 존재한다.
tf_broadcaster.sendTransform(
translation=[10, 10, 0],
rotation=[0., 0., 0., 1],
time=rospy.Time.now(),
child="home",
parent="world"
)
tf_broadcaster.sendTransform(
translation=[10, 10, 0],
rotation=[0., 0., 0., 1],
time=rospy.Time.now(),
child="world",
parent="utm"
)
if tf_listener.canTransform(
target_frame="utm", source_frame="home", time=rospy.Time(0)) and msg is not None:
res = tf_listener.transformPose(ps=msg, target_frame="utm")
rospy.loginfo(res)
또한, 이 역시도 ROS의 일부이기 때문에, 간단하게 시각화 할 수 있다는 점 또한, 장점으로 볼 수 있을 것이다.
$ rosrun tf view_frames
이처럼 frame은 ROS 상에 존재하는 수많은 좌표계를 의미하며, TF는 각 프레임 사이의 관계를 정의하는 것임을 확인하였다. 이런 frame과 TF는 그 구조가 Publisher, Subscriber와 비슷하여 사용하기 매우 쉬우면서도, 좌표간 계산을 줄여줄 수 있는 매우 강력한 도구이다. 이 점을 잘 활용한다면, 로봇의 구조가 복잡하더라도, 매우 쉽고 빠르게 작업을 진행할 수 있을 것이다.
TF는 갓 기능이지만 Stamp가 꼬이면 겁나 고생한다. 처음에 잘 잡아두자...
감사합니다. 도움이 많이 되었어요~~