TF API

1       数据类型

定义在 tf/transform_datatypes.h

1.1   基本数据类型

1.2   tf::Stamped <T>

除了tf::Transform外的带有frame_id_ (坐标系名称std::string stamp_(时间戳ros::Time模板

Stamped(constT& input, constros::Time& timestamp, conststd::string & frame_id);

1.3   tf::StampedTransform

专为tf::Transform设计的带有frame_idstamp以及chrid_frame_id的模板

StampedTransform(consttf::Transform& input, constros::Time& timestamp, conststd::string & frame_id, conststd::string & child_frame_id):
    tf::Transform (input), stamp_ ( timestamp ), frame_id_ (frame_id), child_frame_id_(child_frame_id){ };

1.4   辅助功能

tf::Quaternion createIdentityQuaternion()

  • Return an identity quaternion.

tf::Quaternion createQuaternionFromRPY(double roll,double pitch,double yaw)

  • Return a tf::Quaternion constructed from Fixed-Axis Roll, Pitch and Yaw

geometry_msgs::Quaternion createQuaternionMsgFromRollPitchYaw(double roll,double pitch,double yaw)

  • Return a geometry_msgs::Quaternion constructed from Fixed-Axis Roll, Pitch and Yaw.

 

2       发布tf变换广播

使用tf::TransformBroadcaster

构造函数:

tf::TransformBroadcaster();

发送变换:

voidsendTransform(constStampedTransform & transform);
voidsendTransform(constgeometry_msgs::TransformStamped & transform);

 

3       接受并使用tf广播

tf::TransformListener,继承自tf::Transformer

构造函数:

TransformListener(constros::NodeHandle &nh, ros::Durationmax_cache_time=ros::Duration(DEFAULT_CACHE_TIME), boolspin_thread=true)

TransformListener(ros::Durationmax_cache_time=ros::Duration(DEFAULT_CACHE_TIME), boolspin_thread=true)

canTransform()返回一个表示变换是否可以被计算的布尔量,不会引发异常

booltf::TransformListener::canTransform (conststd::string &target_frame, conststd::string &source_frame, constros::Time &time, std::string *error_msg=NULL) const
booltf::TransformListener::canTransform (conststd::string &target_frame, constros::Time &target_time, conststd::string &source_frame, constros::Time &source_time, conststd::string &fixed_frame, std::string *error_msg=NULL) const

waitForTransform

It will sleep and retry every polling_duration until theduration of timeout has been passed. It will not throw.

booltf::TransformListener::waitForTransform (conststd::string &target_frame, conststd::string &source_frame, constros::Time &time, constros::Duration &timeout, constros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
booltf::TransformListener::waitForTransform (conststd::string &target_frame, constros::Time &target_time, conststd::string &source_frame, constros::Time &source_time, conststd::string &fixed_frame, constros::Duration &timeout, constros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const

lookupTransform

变换保存在transform中,可能会引发tf exception。

voidtf::TransformListener::lookupTransform (conststd::string &target_frame, conststd::string &source_fram, constros::Time &time, StampedTransform &transform) const
voidtf::TransformListener::lookupTransform (conststd::string &target_frame, constros::Time &target_time, conststd::string &source_frame, constros::Time &source_time, conststd::string &fixed_frame, StampedTransform &transform) const

transformDATA Methods

支持的数据类型:

voidtf::TransformListener::transformDATATYPE (conststd::string &target_frame, constgeometry_msgs::DATATYPEStamped &stamped_in, geometry_msgs::DATATYPEStamped &stamped_out) const
voidtf::TransformListener::transformDATATYPE (conststd::string &target_frame, constros::Time &target_time, constgeometry_msgs::DATATYPEStamped &pin, conststd::string &fixed_frame, geometry_msgs::DATATYPEStamped &pout) const

 

4       异常

tf::ConnectivityException

  • Thrown if the request cannot be completed due to the two frame ids not being in the same connected tree.

tf::ExtrapolationException

  • Thrown if there is a connection between the frame ids requested but one or more of the transforms are out of date.

tf::InvalidArgument

  • Thrown if an argument is invalid. The most common case is an unnormalized quaternion.

tf::LookupException

  • Thrown if an unpublished frame id is referenced.

 

评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值