导航:1. sendTransform()--发布tf变换
2. waitForTransform()、lookupTransform() --订阅tf变换
3. tf::StampedTransform() --发送一个 StampedTransform(这是一个类)
4. Transformer::canTransform() --测试 tf 是否possible(可用)
5. Transformer::transformPose ()和Transformer::transformQuaternion()
6. pcl_ros::transformPointCloud()
7. transform() 点在不同坐标系转换
发布tf变换: sendTransform()使用
static tf::TransformBroadcaster br; //加static表静态tf变换
tf::Transform transform;
transform.setOrigin( tf::Vector3(msg->x, msg->y, 0.0) );
tf::Quaternion q;
q.setRPY(0, 0, msg->theta);
transform.setRotation(q);
br.sendTransform(tf::StampedTransform(transform, ros::Time::now(), "world", turtle_name));
函数waitForTransform()、lookupTransform()
这里 waitForTransform() , /turtle2 是target_frame,这里理解为 数据应转换到的frame, 也就是 tf 的 frame_id ; /turtle1 是source_frame ,这里理解为 数据来源的frame, 也就是 tf 的 child_frame_id 。 等待的是 /turtle2 到 /turtle1 的坐标转换,ros::Time(0) 代表最近时刻的有效数据,ros::time::now() 是现在这个时刻的有效数据,不可以把 ros::Time(0) 改成 ros::time::now() ,因为监听做不到实时,会有几毫秒的延迟;最长等待 3.0 s 的时间。
// tf监听器
tf::TransformListener listener;
tf::StampedTransform transform;
try{
// 得到"/turtle1"到"/turtle2"的transfrom,
//使用ros::Time(0)可以返回最新的'turtle1'到'turtl2'的变换
listener.waitForTransform("/turtle2", "/turtle1", ros::Time(0), ros::Duration(3.0));
listener.lookupTransform("/turtle2", "/turtle1", ros::Time(0), transform);
}
catch (tf::TransformException &ex)
{
ROS_ERROR("%s",ex.what());
}
函数StampedTransform()
tf::StampedTransform::StampedTransform (
const tf::Transform & input,
const ros::Time & timestamp,
const std::string & frame_id,
const std::string & child_frame_id
) [inline]
Transformer::canTransform()
测试 tf 是否possible(可用),传入的参数中scan->header.frame_id 是目标坐标系,robot_frame 是源坐标系,scan->header.stamp 是时间戳,error_msg 返回 一个Bool如果 转换(transform) 失败的原因 的标志数据。。链接
boost::shared_ptr<tf::TransformListener> listener;
if (!listener->canTransform(scan->header.frame_id, robot_frame, scan->header.stamp, &error_msg))
{
ROS_ERROR_STREAM_THROTTLE(1.0, "can not transform: "<<robot_frame<<" to "<<scan->header.frame_id);
return;
}
函数 Transformer::transformPose ()、Transformer::transformQuaternion()
目标坐标系、ident 是输入的带时间戳的位姿、laser_pose 是输出的 带时间戳的位姿。 查找了一个目标坐标系base_frame_id_ 到 ident 中的源坐标系laser 之间的 tf, ident 的中的tf转换数据会被赋值到 laser_pose 中。。
TransformListenerWrapper* tf_;
tf::Stamped<tf::Pose> ident (tf::Transform(tf::createIdentityQuaternion(),
tf::Vector3(0,0,0)),
ros::Time(), laser_scan->header.frame_id);
tf::Stamped<tf::Pose> laser_pose;
tf_->transformPose(base_frame_id_, ident, laser_pose);
pcl_ros::transformPointCloud()
其中第一个参数为目标坐标系,第二个参数为原始点云,第三个参数为 目标点云,
第四个参数为接收到的坐标,正变换、逆变换 都包含其中
pcl_ros::transformPointCloud("/velodyne", *input_cloud, *output_cloud, *tran);
transform() 点在不同坐标系转换
#include "tf2_ros/transform_listener.h"
#include "tf2_ros/buffer.h"
#include "geometry_msgs/PointStamped.h"
#include "tf2_geometry_msgs/tf2_geometry_msgs.h" //注意: 调用 transform 必须包含该头文件
// 3.创建 TF 订阅节点
tf2_ros::Buffer buffer;
tf2_ros::TransformListener listener(buffer);
// 4.生成一个坐标点(相对于子级坐标系)
geometry_msgs::PointStamped point_laser;
point_laser.header.frame_id = "turtle1";
point_laser.header.stamp = ros::Time();
point_laser.point.x = 1;
point_laser.point.y = 1;
point_laser.point.z = 0;
try
{
geometry_msgs::PointStamped point_base;
point_base = buffer.transform(point_laser,"world");
ROS_INFO("坐标点相对于 world 的坐标为:(%.2f,%.2f,%.2f)",point_base.point.x,point_base.point.y,point_base.point.z);
}
catch(const std::exception& e)
{
// std::cerr << e.what() << '\n';
ROS_INFO("程序异常:%s",e.what());
}