StampedTransform函数参数定义
ros::Time stamp_; ///< The timestamp associated with this transform
std::string frame_id_; ///< The frame_id of the coordinate frame in which this transform is defined
std::string child_frame_id_; ///< The frame_id of the coordinate frame this transform defines
StampedTransform(const tf::Transform& input, const ros::Time& timestamp, const std::string & frame_id, const std::string & child_frame_id):
tf::Transform (input), stamp_ ( timestamp ), frame_id_ (frame_id), child_frame_id_(child_frame_id){ }
transformPoint函数参数定义
/** \brief Transform a Stamped Point Message into the target frame
* This can throw all that lookupTransform can throw as well as tf::InvalidTransform */
void transformPoint(const std::string& target_frame, const geometry_msgs::PointStamped& stamped_in, geometry_msgs::PointStamped& stamped_out) const;
参数收发的小例子:
tf_broadcaster.cpp
#include <ros/ros.h>
#include <tf/transform_broadcaster.h>
int main(int argc, char** argv) {
ros::init(argc, argv, "robot_tf_publisher");
ros::NodeHandle n;
ros::Rate r(100);
tf::TransformBroadcaster broadcaster;
while (n.ok()) {
tf::Transform transform; //这里transform为一个类
tf::Quaternion q; // Quaternion是一个类
q.setRPY(0.0, 0.0, 0.0);
// setRPY是类Quaternion的一个成员函数 rpy 转换为四元数
transform.setRotation(q);
transform.setOrigin(tf::Vector3(0.1, 0.0, 0.2));
broadcaster.sendTransform(tf::StampedTransform(transform, ros::Time::now(),
"base_link", "base_laser"));
r.sleep();
}
}
tf_listener.cpp
#include <geometry_msgs/PointStamped.h>
#include <ros/ros.h>
#include <tf/transform_listener.h>
void transformPoint(const tf::TransformListener& listener) {
// we'll create a point in the base_laser frame that we'd like to transform to
// the base_link frame
geometry_msgs::PointStamped laser_point;
laser_point.header.frame_id = "base_laser";
// we'll just use the most recent transform available for our simple example
laser_point.header.stamp = ros::Time();
// just an arbitrary point in space
static int x = 1;
laser_point.point.x = x++;
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));
// we'll transform a point once every second
ros::Timer timer = n.createTimer(
ros::Duration(1.0), boost::bind(&transformPoint, boost::ref(listener)));
ros::spin();
}