728x90
- tf는 Transformation의 약자로, 로봇상의 다수의 서로 다른 3D Coordinate Frames를 추적할 수 있도록 하는 package이다
- 위의 사진과 같이 로봇에는 수많은 3D coordinate frames가 있으며, 각 frames은 시간이 지남에 따라 변화한다
- tf는 이러한 frame들을 계속 추적하여 각 frame들간의 상대적인 위치를 기록한다
- tf는 분리된 system에서 동작이 가능하다 : robot의 모든 coordinate frames에 관한 정보는 다른 모든 ROS components에서도 사용 가능하다
- transform information에는 central server가 없다
- tf tree는 서로 다른 coordinate frame간의 변환 및 회전 측면에서 offset을 추상적인 수준으로 정의한다
- 예제
- 로봇의 중심점에 위치하는 coordinate frame을 base_link라 하고 laser sensor의 중심점에 위치하는 coordinate frame을 base_laser라고 하자
- Navigation을 위해선 base_link가 로봇의 회전 중심에 위치하는 것이 중요하다)
- Robot 구동시 laser sensor를 통해 얻은 data를 바탕으로 장애물을 회피하고자 하면 base_laser 위치에서 받은 data를 base_link frame으로 변환시켜야 한다. 즉 두 frame간의 relationship을 정의해야 한다
- 위 사진에서 볼 수 있듯 두 frame 사이에는 x축 방향으로 10cm, z축 방향으로 20cm의 거리 차이가 있다
- 이 값들이 두 frame간의 translational offset이 된다
- offset에는 각 frame들간의 회전과 평행이동에 대한 정보들이 있다 (위 사진의 경우 회전은 X)
- 위처럼 'base_link'에 해당하는 node와 'base_laser'에 해당하는 node를 생성한다
- 그리고 둘 중 어떤 node가 parent가 되고 child가 될 지 결정한다. tf는 모든 transform이 parent에서 child로 간다고 가정한다
- 위의 경우는 'base_link' node를 parent로 정하였다
- 다른 sensor가 robot에 추가되면 base_link frame을 통해 base_laser frame과 연관되는 것이 가장 합리적이다
- 코드 작성
- 우선 transform을 publish할 node와, 그 node에서 publish된 transform data를 listen하고 transform point에 적용시킬 node를 만들어야 한다
- roscpp, tf, geometry_msgs의 dependency들을 가지는 'robot_setup_tf'라는 이름의 package를 생성한다
$ cd ~/catkin_ws/src
$ catkin_create_pkg robot_setup_tf roscpp tf geometry_msgs
- ROS를 통해 base_laser -> base_link로의 transform을 broadcast할 node를 만든다
$ cd robot_setup_tf/src
$ gedit tf_broadcaster.cpp
- 해당 file에 아래의 내용을 입력한다
#include <ros/ros.h>
#include <tf/transform_broadcaster.h> // tf package에서 제공하는 보다 편한 tf를 위한 header file 사용
int main(int argc, char** argv){
ros::init(argc, argv, "robot_tf_publisher"); // node 이름 : robot_tf_publisher
ros::NodeHandle n; // ROS 시스템과의 통신을 위한 node handle 선언
ros::Rate r(100);
tf::TransformBroadcaster broadcaster;
// base_link -> base_laser로 tf를 보낼 때 사용할 broadcaster라는 이름의 TFBroadcaster object 선언
while(n.ok()){ // 실제로 tf가 수행되는 부분
broadcaster.sendTransform(
tf::StampedTransform(
tf::Transform(tf::Quaternion(0, 0, 0, 1), tf::Vector3(0.1, 0.0, 0.2)),
// Quaternion의 parameter는 순서대로 ptich, roll, yaw,
// Vector3의 parameter는 meter단위
ros::Time::now(),"base_link", "base_laser"));
// TF에 timestamp, parent node와 child node의 이름 전달
r.sleep();
}
}
- TransformBroadcaster로 transform을 보낼 땐 아래의 5가지 argument들이 필요하다
- 두 coordinate frame 간의 Quaternion으로 지정되는 Rotation Transform. 지금은 회전이 없으므로 Quaternion 함수에 pitch, roll, yaw값을 0을 준다
- 우리가 적용할 모든 translation을 위한 btVerctor3. 현재 robot의 base에 대한 laser의 x, y, z offset을 입력한다
- Publish되는 transform에 전달할 timestamp(특정 시간을 기록하는 문자열). ros::Time::now()를 통해 준다
- 생성한 link에 전달할 parent node의 이름(base_link)
- 생성한 link에 전달할 child node의 이름(base_laser)
- ROS를 통해 base_laser -> base_link 를 publish할 node 생성 완료
- base_laser frame에 점을 찍고 base_link로 transform 하기 위해 위의 transform을 사용할 node 생성
$ gedit tf_listener.cpp
- 아래 내용 입력
#include <ros/ros.h>
#include <geometry_msgs/PointStamped.h>
#include <tf/transform_listener.h> // TransformListener 생성을 위한 header file
// TransformListener가 주어지면 "base_laser" frame의 한 지점을 가져와 "base_link" frame으로 변환하는 함수 생성
// 이 함수는 프로그램의 main()에서 생성된 ros::Timer에 대한 callback 역할을 하여 매초마다 실행됨
void transformPoint (const tf::TransformListener& listener){
// base_link frame으로 transform할 base_laser frame내의 point 생성
// 'Stamped'라는 단어는 단지 message에 header가 포함되어 있어 timestamp와 frame_id를 message와 연결할 수 있음을 의미
geometry_msgs::PointStamped laser_point;
// base_laser frame내의 점을 생성하므로 header의 frame_id를 base_laser로 설정
laser_point.header.frame_id = "base_laser";
// 예제를 위해 가장 최근의 사용 가능한 transform 사용
// laser_point의 stamp filed가 TramsfprmListener에게 최신의 이용 가능한 transform을 요청할 수 있게 해주는
// 특별한 시간 값인 ros::Time()이 되도록 설정함.
laser_point.header.stamp = ros::Time();
// base_laser frame 내의 point (laser의 base_link에 대한 상대적 거리값)
laser_point.point.x = 1.0;
laser_point.point.y = 0.2;
laser_point.point.z = 0.0;
try{
geometry_msgs::PointStamped base_point;
listener.transformPoint("base_link", laser_point, base_point);
ROS_INFO("base_laser: (%.2f, %.2f. %.2f) -----> base_link: (%.2f, %.2f, %.2f) at time %.2f",
laser_point.point.x, laser_point.point.y, laser_point.point.z,
base_point.point.x, base_point.point.y, base_point.point.z, base_point.header.stamp.toSec());
}
// transform 오류 확인용. transform이 제대로 되지 않았을 경우 TransformListener는 아래의 exception을 실행시킴
catch(tf::TransformException& ex){
ROS_ERROR("Received an exception trying to transform a point from \"base_laser\"to \"base_link\": %s", ex.what());
}
}
int main(int argc, char** argv){
ros::init(argc, argv, "robot_tf_listener");
ros::NodeHandle n;
tf::TransformListener listener(ros::Duration(10));
// 1초마다 한 점을 transform
ros::Timer timer = n.createTimer(ros::Duration(1.0), boost::bind(&transformPoint, boost::ref(listener)));
ros::spin();
}
- TransformListener object는 자동적으로 ROS로부터의 transform message topic을 subscribe하고 전해지는 모든 transform data를 관리함
- transformPoint의 argument는 아래와 같음
- target_frame : point를 transform할 frame의 이름(여기선 base_link)
- stamped_in : tranform하고 있는 point의 frame
- stamped_out : transform된 point의 storage. 함수 호출 이후에는 base_link frame 내에서만 이전의 laser_point와 동일한 값을 가짐
- 위의 source code 작성 완료 후, build를 위해 CMakeLists.txt를 염
$ cd ..
$ gedit CMakeLists.txt
- 아래 내용을 맨 아랫 부분에 추가
add_executable(tf_broadcaster src/tf_broadcaster.cpp)
add_executable(tf_listener src/tf_listener.cpp)
target_link_libraries(tf_broadcaster ${catkin_LIBRARIES})
target_link_libraries(tf_listener ${catkin_LIBRARIES})
$ cd ~/catkin_ws
$ catkin_make
- Package compile
- 코드 실행
$ roscore
$ rosrun robot_setup_tf tf_broadcaster
$ rosrun robot_setup_tf tf_listener
- 각각 다른 terminal 창에서 위의 명령어들 실행
- 아래와 같은 출력이 나오면 정상
[ INFO] 1248138528.200823000: base_laser: (1.00, 0.20. 0.00) -----> base_link: (1.10, 0.20, 0.20) at time 1248138528.19
[ INFO] 1248138529.200820000: base_laser: (1.00, 0.20. 0.00) -----> base_link: (1.10, 0.20, 0.20) at time 1248138529.19
[ INFO] 1248138530.200821000: base_laser: (1.00, 0.20. 0.00) -----> base_link: (1.10, 0.20, 0.20) at time 1248138530.19
[ INFO] 1248138531.200835000: base_laser: (1.00, 0.20. 0.00) -----> base_link: (1.10, 0.20, 0.20) at time 1248138531.19
[ INFO] 1248138532.200849000: base_laser: (1.00, 0.20. 0.00) -----> base_link: (1.10, 0.20, 0.20) at time 1248138532.19
- 1초마다 transform이 되고 있다
- 위처럼 tf를 이용해 서로 다른 두 frame들간의 관계를 정의할 수 있다
- tf는 tree구조를 이용해 서로 다른 frame들 사이의 관계를 일방통행 방식으로 정의한다
- tf tree가 한번 형성되면, tf library 호출을 통해 간단하게 laser sensor의 data를 base_link frame으로 변환할 수 있다
- 로봇에 다른 센서들을 부착하여 사용해야 하므로 보통 base_link frame같은 로봇의 중심에 위치하는 frame을 부모로 많이 사용한다
참고 자료 :
https://velog.io/@richard7714/ROS-Navigation-tf
'Study_ROS' 카테고리의 다른 글
Cartographer/Hector SLAM 사용법 (0) | 2023.02.05 |
---|---|
Ubuntu 20.04에 ROS Noetic 설치법 (0) | 2023.01.21 |
우분투에서 Arduino IDE를 통한 rosserial 사용법 (0) | 2022.11.05 |
Tutorial of ROS (0) | 2022.10.29 |
Ubuntu 20.04에서 IDE(Visual Studio Code, Qtcreator)를 통한 ROS 개발환경 구축 (0) | 2022.09.17 |