tf to kdl

hi,

I'm looking for the easiest (the least number of transformations) to get a KDL::Frame out of a tf::StampedTransform,
but it needs to be passed over a topic in between.

There is:
tf::PoseMsgToKDL( const geometry_msgs::Pose & p, KDL::Frame & t )
tf::TransformTFToKDL( const tf::Transform & t, KDL::Frame & k )

The first would result in:
tf::StampedTransform => ??? => geometry_msgs::Pose => 'communication over topic' => tf::PoseMsgToKDL => KDL::Frame
But how to do the ??? part nicely? (for some reason tf makes distinction between transform and pose)

the latter would result in:
tf::StampedTransform => tf::Transform => tf::TransformTFToKDL => KDL::Frame => geometry_msgs::Pose => 'communication over topic' => tf::PoseMsgToKDL => KDL::Frame
But this is huge overhead with the unnecessary transformations between KDL::Frame and geometry_msgs::Pose.

It seems that there is no tf::StampedTransform message type nor KDL::Frame message type, which would simplify the issue, correct?

suggestions?

thanks in advance

Nick

Ruben Smits's picture

tf to kdl

Hi Nick,

On Mon, Oct 28, 2013 at 7:38 PM, Dominick Vanthienen
<dominick [dot] vanthienen [..] ...> wrote:
> hi,
>
> I'm looking for the easiest (the least number of transformations) to get a KDL::Frame out of a tf::StampedTransform,
> but it needs to be passed over a topic in between.
>
> There is:
> tf::PoseMsgToKDL( const geometry_msgs::Pose & p, KDL::Frame & t )
> tf::TransformTFToKDL( const tf::Transform & t, KDL::Frame & k )
>
> The first would result in:
> tf::StampedTransform => ??? => geometry_msgs::Pose => 'communication over topic' => tf::PoseMsgToKDL => KDL::Frame
> But how to do the ??? part nicely? (for some reason tf makes distinction between transform and pose)
>
> the latter would result in:
> tf::StampedTransform => tf::Transform => tf::TransformTFToKDL => KDL::Frame => geometry_msgs::Pose => 'communication over topic' => tf::PoseMsgToKDL => KDL::Frame
> But this is huge overhead with the unnecessary transformations between KDL::Frame and geometry_msgs::Pose.
>
> It seems that there is no tf::StampedTransform message type nor KDL::Frame message type, which would simplify the issue, correct?

You can use the geometry_msgs/StampedTranform msgs and the following
conversion function:
(from tf/transform_datatypes.h)
static void tf::transformStampedTFToMsg (const StampedTransform &bt,
geometry_msgs::TransformStamped &msg)

Send that over the topic and than use
(from kdl_conversions/kdl_msg.h)
void transformMsgToKDL(const geometry_msgs::Transform &m, KDL::Frame &k)

to convert the transformMsg to a KDL frame;

Seems the be the lease amount of conversions to me (2!).

Ruben

> suggestions?
>
> thanks in advance
>
> Nick
> --
> Orocos-Users mailing list
> Orocos-Users [..] ...
> http://lists.mech.kuleuven.be/mailman/listinfo/orocos-users

tf to kdl

On 10/28/2013 08:13 PM, Ruben Smits wrote:
> Hi Nick,
>
>
>
> On Mon, Oct 28, 2013 at 7:38 PM, Dominick Vanthienen
> <dominick [dot] vanthienen [..] ...> wrote:
>> hi,
>>
>> I'm looking for the easiest (the least number of transformations) to get a KDL::Frame out of a tf::StampedTransform,
>> but it needs to be passed over a topic in between.
>>
>> There is:
>> tf::PoseMsgToKDL( const geometry_msgs::Pose & p, KDL::Frame & t )
>> tf::TransformTFToKDL( const tf::Transform & t, KDL::Frame & k )
>>
>> The first would result in:
>> tf::StampedTransform => ??? => geometry_msgs::Pose => 'communication over topic' => tf::PoseMsgToKDL => KDL::Frame
>> But how to do the ??? part nicely? (for some reason tf makes distinction between transform and pose)
>>
>> the latter would result in:
>> tf::StampedTransform => tf::Transform => tf::TransformTFToKDL => KDL::Frame => geometry_msgs::Pose => 'communication over topic' => tf::PoseMsgToKDL => KDL::Frame
>> But this is huge overhead with the unnecessary transformations between KDL::Frame and geometry_msgs::Pose.
>>
>> It seems that there is no tf::StampedTransform message type nor KDL::Frame message type, which would simplify the issue, correct?
>
> You can use the geometry_msgs/StampedTranform msgs and the following
> conversion function:
> (from tf/transform_datatypes.h)
> static void tf::transformStampedTFToMsg (const StampedTransform &bt,
> geometry_msgs::TransformStamped &msg)
>
> Send that over the topic and than use
> (from kdl_conversions/kdl_msg.h)
> void transformMsgToKDL(const geometry_msgs::Transform &m, KDL::Frame &k)
>
> to convert the transformMsg to a KDL frame;
>
> Seems the be the lease amount of conversions to me (2!).
thanks, I didn't see this transform on the wiki
it basically does what I proposed in the other mail :)

>
> Ruben
>
>> suggestions?
>>
>> thanks in advance
>>
>> Nick
>> --
>> Orocos-Users mailing list
>> Orocos-Users [..] ...
>> http://lists.mech.kuleuven.be/mailman/listinfo/orocos-users
>
>
>

tf to kdl

On 10/28/2013 07:38 PM, Dominick Vanthienen wrote:
> hi,
>
> I'm looking for the easiest (the least number of transformations) to get a KDL::Frame out of a tf::StampedTransform,
> but it needs to be passed over a topic in between.
>
> There is:
> tf::PoseMsgToKDL( const geometry_msgs::Pose & p, KDL::Frame & t )
> tf::TransformTFToKDL( const tf::Transform & t, KDL::Frame & k )
>
> The first would result in:
> tf::StampedTransform => ??? => geometry_msgs::Pose => 'communication over topic' => tf::PoseMsgToKDL => KDL::Frame
> But how to do the ??? part nicely? (for some reason tf makes distinction between transform and pose)
>
> the latter would result in:
> tf::StampedTransform => tf::Transform => tf::TransformTFToKDL => KDL::Frame => geometry_msgs::Pose => 'communication over topic' => tf::PoseMsgToKDL => KDL::Frame
> But this is huge overhead with the unnecessary transformations between KDL::Frame and geometry_msgs::Pose.
>
> It seems that there is no tf::StampedTransform message type nor KDL::Frame message type, which would simplify the issue, correct?

there is a third way (the one I use at the moment)
tf::StampedTransform => tf::transformStampedTFToMsg => geometry_msgs::TransformStamped => 'communication over topic' =>
pose.p.x(ext_pose_tf.transform.translation.x);
pose.p.y(ext_pose_tf.transform.translation.y);
pose.p.z(ext_pose_tf.transform.translation.z);
pose.M.Quaternion(ext_pose_tf.transform.rotation.x, ext_pose_tf.transform.rotation.y, ext_pose_tf.transform.rotation.z, ext_pose_tf.transform.rotation.w);
=>KDL::Frame pose

>
> suggestions?
>
> thanks in advance
>
> Nick
>