ROS tf tree๋ฅผ ์์๋ณด์!
Robot system์๋ ์๋ง์ 3D coordinates๋ค์ด ์กด์ฌ
tf๋ ๋ง์ frame๋ค์ ๊ณ์ trackingํ์ฌ frame๋ค๊ฐ ์๋์ ์ธ ์์น๋ฅผ ๊ณ์ ๊ธฐ๋ก
tf๋ distributed system์์ ๊ตฌ๋๋๊ธฐ ๋๋ฌธ์, ๋ก๋ด์ coordinate์ ๋ํ ๋ชจ๋ ์ ๋ณด๋ ๋ค๋ฅธ ๋ชจ๋ ROS component๋ค๋ ์ฌ์ฉํ ์ ์์
์ฆ, transform information์ ์ค์ฌ์๋ฒ๊ฐ ์กด์ฌํ์ง ์์
์ฌ๊ธฐ์ ๋ก๋ด์ ์ค์ ์ค์ฌ๋ base_link
์ด๊ณ ์ค์บ๋์ ์ขํ ์ค์ฌ์ base_laser
์
๋ฐ๋ผ์ ๋ผ์ด๋ค๋ก๋ถํฐ ์ค์บ๋ ์ ๋ณด๋ฅผ ๋ก๋ด ์ค์ฌ์์์ ์ขํ๋ก transformationํ๋ ๊ณผ์ ์ด ํ์ํจ!
odom
-> base_footprint
-> base_link
-> sensor_link
์์ด๋ค!!!
์ด๋ฅผ ์ฝ๊ฒ ํด์ฃผ๋ ๊ฒ์ด ๋ฐ๋ก tf library ์
In ${workspace}/src
$ catkin_create_pkg robot_setup_tf roscpp tf geometry_msgs
#include <ros/ros.h>
#include <tf/transform_broadcaster.h>
using namespace std;
int main(int argc, char** argv)
{
ros::init(argc, argv, "tf_broadcaster");
ros::NodeHandle nh;
ros::Rate r(100);
tf::TransformBroadcaster broadcaster;
while(nh.ok())
{
broadcaster.sendTransform(
tf::StampedTransform(
tf::Transform(tf::Quaternion(0,0,0,1), tf::Vector3(0.1, 0.0, 0.2)),
ros::Time::now(), "based_link", "base_laser"));
}
return 0;
}
TransformBroadcaster๋ฅผ ํตํด transform์ ์ก์ ํ๋ ค๋ฉด 5๊ฐ์ argument๊ฐ ํ์
#include <ros/ros.h>
#include <tf/transform_listener.h>
#include <geometry_msgs/PointStamped.h>
using namespace std;
void transformPoint(const tf::TransformListener& listener)
{
geometry_msgs::PointStamped laser_point;
laser_point.header.frame_id = "base_laser";
laser_point.header.stamp = ros::Time();
// just an arbitrary point
laser_point.point.x = 1.0;
laser_point.point.x = 0.2;
laser_point.point.x = 3;
try
{
geometry_msgs::PointStamped base_point;
listener.transformPoint("based_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());
}
catch(const tf::TransformException& ex) //catch(const std::exception& e)
{
// std::cerr << e.what() << '\n';
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, "tf_listener");
ros::NodeHandle nh;
tf::TransformListener listener(ros::Duration(10));
// 1์ด์ a point๋ฅผ Transform ํ ๊ฑฐ์
ros::Timer timer = nh.createTimer(ros::Duration(1.0), boost::bind(&transformPoint, boost::ref(listener)));
return 0;
}
add_executable(tf_broadcaster src/tf_broadcaster.cpp)
target_link_libraries(tf_broadcaster
${catkin_LIBRARIES}
)
add_executable(tf_listener src/tf_listener.cpp)
target_link_libraries(tf_listener
${catkin_LIBRARIES}
)
$ roscore
$ rosrun robot_tf_tutorial tf_broadcaster
$ rosrun robot_tf_tutorial tf_listener
<!-- Create a transform sender for linking these frames. -->
<node name="tf_footprint_base" pkg="tf" type="static_transform_publisher" args="0 0 0 0 0 0 base_footprint base_link 40" />
์ด๊ฑธ๋ก ์ฝ๊ฒ ํ์โฆ.
x y z r p y frame_id child_id Hz