在ROS工作空间ROS_ws的src文件夹目录下创建一个功能包,命名为tf_lidar_task,并编译完成。
广播并监听机器人的坐标变换,已知激光雷达和机器人底盘的坐标关系,求解激光雷达数据在底盘坐标系下的坐标值。
在功能包下面的src文件夹目录下创建一个空文件lidar_broadcaster.cpp,并打开所创建的文件,输入以下代码。
#include
#include
int main(int argc, char** argv)
{
//初始化ROS节点
ros::init(argc, argv, "robot_tf_publisher");
//创建节点句柄
ros::NodeHandle n;
//设置TF广播频率为100Hz
ros::Rate r(100);
//创建tf::TransformBroadcaster类的对象
tf::TransformBroadcaster broadcaster;
while(n.ok())
{
//广播TF坐标系变换关系到ROS系统中
broadcaster.sendTransform( tf::StampedTransform( tf::Transform(tf::Quaternion(0, 0, 0, 1), tf::Vector3(0.1, 0.0, 0.2)), ros::Time::now(), "base_link", "base_laser"));
r.sleep();
}
}
说明:
相关资料:http://wiki.ros.org/navigation/Tutorials/RobotSetup/TF
在功能包下面的src文件夹目录下创建一个空文件lidar_listener.cpp,并打开所创建的文件,输入以下代码。
#include
#include
#include
//当接收到TF消息时,自动调用该回调函数
void transformPoint(const tf::TransformListener& listener)
{
geometry_msgs::PointStamped laser_point;
laser_point.header.frame_id = "base_laser";
laser_point.header.stamp = ros::Time();
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());
}
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));
ros::Timer timer = n.createTimer(ros::Duration(1.0), boost::bind(&transformPoint, boost::ref(listener)));
ros::spin();
}
说明:
geometry_msgs::PointStamped laser_point;
laser_point.header.frame_id = "base_laser";
laser_point.header.stamp = ros::Time();
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());
}
这里使用tf::TransformListener类的对象中的transformPoint()函数,将虚拟点的坐标数据从base_laser参考系转换到base_link参考系下,该函数包含三个参数。
该函数执行完毕后,base_point中就包含了变换完成后的点坐标了,最后通过ROS_INFO()将坐标信息打印在ROS终端界面。
catch(tf::TransformException& ex)
{
ROS_ERROR("Received an exception trying to transform a point from \"base_laser\" to \"base_link\": %s", ex.what());
}
将如下位置中CATLIN_DEPENDS前面的“#”去掉,使能相关的依赖项。
在如下位置进行配置,add_executable(lidar_broadcaster src/lidar_broadcaster.cpp)的作用是将src文件夹下的lidar_broadcaster.cpp文件编译成名为lidar_broadcaster的可执行文件。target_link_libraries(lidar_broadcaster ${catkin_LIBRARIES})的作用是将lidar_broadcaster可执行文件与ROS相关的库链接。
add_executable(lidar_broadcaster src/lidar_broadcaster.cpp)
add_executable(lidar_listener src/lidar_listener.cpp)
target_link_libraries(lidar_broadcaster ${catkin_LIBRARIES})
target_link_libraries(lidar_listener ${catkin_LIBRARIES})
在/ROS_ws文件夹路径下打开一个新的终端,输入以下代码进行编译。
$ catkin_make
编译完成后,输入以下代码运行主节点。
$ roscore
打开一个新的终端,配置环境变量后,输入以下代码运行TF广播器。
$ rosrun tf_lidar_task lidar_listener
打开一个新的终端,配置环境变量后,输入以下代码运行TF监听者。
$ rosrun tf_lidar_task lidar_broadcaster
若想停止运行,关闭终端,使用快捷键Ctrl+c即可。
在src文件夹路径下打开一个新的终端,输入以下代码。
$ rosrun tf view_frames
由此可以生成一个名为frames的pdf文件,直观地看到TF变换时的坐标系关系。
$ rosrun rqt_tf_tree rqt_tf_tree
该命令是动态的查询当前的tf tree,当前的任何变化都能当即看到,例如何时断开何时连接,捕捉到这些然后通过rqt插件显示出来。
$ rostopic echo /tf
该命令的作用是以TransformStamped消息类型的数组显示所有父子frame的位姿转换关系。
$ rosrun tf tf_echo base_laser base_link