Program Listing for File tf2_kdl.hpp

Return to documentation for file (/tmp/ws/src/geometry2/tf2_kdl/include/tf2_kdl/tf2_kdl.hpp)

// Copyright 2008 Willow Garage, Inc.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
//
//    * Redistributions of source code must retain the above copyright
//      notice, this list of conditions and the following disclaimer.
//
//    * Redistributions in binary form must reproduce the above copyright
//      notice, this list of conditions and the following disclaimer in the
//      documentation and/or other materials provided with the distribution.
//
//    * Neither the name of the Willow Garage, Inc. nor the names of its
//      contributors may be used to endorse or promote products derived from
//      this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.


#ifndef TF2_KDL_HPP
#define TF2_KDL_HPP

#include <tf2/convert.h>
#include <tf2_ros/buffer_interface.h>
#include <kdl/frames.hpp>
#include <geometry_msgs/msg/point_stamped.hpp>
#include <geometry_msgs/msg/twist_stamped.hpp>
#include <geometry_msgs/msg/wrench_stamped.hpp>
#include <geometry_msgs/msg/pose.hpp>
#include <geometry_msgs/msg/pose_stamped.hpp>
#include <builtin_interfaces/msg/time.hpp>
#include <geometry_msgs/msg/transform_stamped.hpp>

namespace tf2
{
inline
KDL::Frame transformToKDL(const geometry_msgs::msg::TransformStamped& t)
  {
    return KDL::Frame(KDL::Rotation::Quaternion(t.transform.rotation.x, t.transform.rotation.y,
                        t.transform.rotation.z, t.transform.rotation.w),
              KDL::Vector(t.transform.translation.x, t.transform.translation.y, t.transform.translation.z));
  }

inline
geometry_msgs::msg::TransformStamped kdlToTransform(const KDL::Frame& k)
{
  geometry_msgs::msg::TransformStamped t;
  t.transform.translation.x = k.p.x();
  t.transform.translation.y = k.p.y();
  t.transform.translation.z = k.p.z();
  k.M.GetQuaternion(t.transform.rotation.x, t.transform.rotation.y, t.transform.rotation.z, t.transform.rotation.w);
  return t;
}

// ---------------------
// Vector
// ---------------------
template <>
inline
  void doTransform(const tf2::Stamped<KDL::Vector>& t_in, tf2::Stamped<KDL::Vector>& t_out, const geometry_msgs::msg::TransformStamped& transform)
  {
    t_out = tf2::Stamped<KDL::Vector>(transformToKDL(transform) * t_in, tf2_ros::fromMsg(transform.header.stamp), transform.header.frame_id);
  }

inline
geometry_msgs::msg::PointStamped toMsg(const tf2::Stamped<KDL::Vector>& in)
{
  geometry_msgs::msg::PointStamped msg;
  msg.header.stamp = tf2_ros::toMsg(in.stamp_);
  msg.header.frame_id = in.frame_id_;
  msg.point.x = in[0];
  msg.point.y = in[1];
  msg.point.z = in[2];
  return msg;
}

inline
void fromMsg(const geometry_msgs::msg::PointStamped& msg, tf2::Stamped<KDL::Vector>& out)
{
  out.stamp_ = tf2_ros::fromMsg(msg.header.stamp);
  out.frame_id_ = msg.header.frame_id;
  out[0] = msg.point.x;
  out[1] = msg.point.y;
  out[2] = msg.point.z;
}

// ---------------------
// Twist
// ---------------------
template <>
inline
  void doTransform(const tf2::Stamped<KDL::Twist>& t_in, tf2::Stamped<KDL::Twist>& t_out, const geometry_msgs::msg::TransformStamped& transform)
  {
    t_out = tf2::Stamped<KDL::Twist>(transformToKDL(transform) * t_in, tf2_ros::fromMsg(transform.header.stamp), transform.header.frame_id);
  }

inline
geometry_msgs::msg::TwistStamped toMsg(const tf2::Stamped<KDL::Twist>& in)
{
  geometry_msgs::msg::TwistStamped msg;
  msg.header.stamp = tf2_ros::toMsg(in.stamp_);
  msg.header.frame_id = in.frame_id_;
  msg.twist.linear.x = in.vel[0];
  msg.twist.linear.y = in.vel[1];
  msg.twist.linear.z = in.vel[2];
  msg.twist.angular.x = in.rot[0];
  msg.twist.angular.y = in.rot[1];
  msg.twist.angular.z = in.rot[2];
  return msg;
}

inline
void fromMsg(const geometry_msgs::msg::TwistStamped& msg, tf2::Stamped<KDL::Twist>& out)
{
  out.stamp_ = tf2_ros::fromMsg(msg.header.stamp);
  out.frame_id_ = msg.header.frame_id;
  out.vel[0] = msg.twist.linear.x;
  out.vel[1] = msg.twist.linear.y;
  out.vel[2] = msg.twist.linear.z;
  out.rot[0] = msg.twist.angular.x;
  out.rot[1] = msg.twist.angular.y;
  out.rot[2] = msg.twist.angular.z;
}


// ---------------------
// Wrench
// ---------------------
template <>
inline
  void doTransform(const tf2::Stamped<KDL::Wrench>& t_in, tf2::Stamped<KDL::Wrench>& t_out, const geometry_msgs::msg::TransformStamped& transform)
  {
    t_out = tf2::Stamped<KDL::Wrench>(transformToKDL(transform) * t_in,  tf2_ros::fromMsg(transform.header.stamp), transform.header.frame_id);
  }

inline
geometry_msgs::msg::WrenchStamped toMsg(const tf2::Stamped<KDL::Wrench>& in)
{
  geometry_msgs::msg::WrenchStamped msg;
  msg.header.stamp = tf2_ros::toMsg(in.stamp_);
  msg.header.frame_id = in.frame_id_;
  msg.wrench.force.x = in.force[0];
  msg.wrench.force.y = in.force[1];
  msg.wrench.force.z = in.force[2];
  msg.wrench.torque.x = in.torque[0];
  msg.wrench.torque.y = in.torque[1];
  msg.wrench.torque.z = in.torque[2];
  return msg;
}

inline
void fromMsg(const geometry_msgs::msg::WrenchStamped& msg, tf2::Stamped<KDL::Wrench>& out)
{
  out.stamp_ = tf2_ros::fromMsg(msg.header.stamp);
  out.frame_id_ = msg.header.frame_id;
  out.force[0] = msg.wrench.force.x;
  out.force[1] = msg.wrench.force.y;
  out.force[2] = msg.wrench.force.z;
  out.torque[0] = msg.wrench.torque.x;
  out.torque[1] = msg.wrench.torque.y;
  out.torque[2] = msg.wrench.torque.z;
}




// ---------------------
// Frame
// ---------------------
template <>
inline
  void doTransform(const tf2::Stamped<KDL::Frame>& t_in, tf2::Stamped<KDL::Frame>& t_out, const geometry_msgs::msg::TransformStamped& transform)
  {
    t_out = tf2::Stamped<KDL::Frame>(transformToKDL(transform) * t_in,  tf2_ros::fromMsg(transform.header.stamp), transform.header.frame_id);
  }

inline
geometry_msgs::msg::Pose toMsg(const KDL::Frame& in)
{
  geometry_msgs::msg::Pose msg;
  msg.position.x = in.p[0];
  msg.position.y = in.p[1];
  msg.position.z = in.p[2];
  in.M.GetQuaternion(msg.orientation.x, msg.orientation.y, msg.orientation.z, msg.orientation.w);
  return msg;
}

inline
void fromMsg(const geometry_msgs::msg::Pose& msg, KDL::Frame& out)
{
  out.p[0] = msg.position.x;
  out.p[1] = msg.position.y;
  out.p[2] = msg.position.z;
  out.M = KDL::Rotation::Quaternion(msg.orientation.x, msg.orientation.y, msg.orientation.z, msg.orientation.w);
}

inline
geometry_msgs::msg::PoseStamped toMsg(const tf2::Stamped<KDL::Frame>& in)
{
  geometry_msgs::msg::PoseStamped msg;
  msg.header.stamp = tf2_ros::toMsg(in.stamp_);
  msg.header.frame_id = in.frame_id_;
  msg.pose = toMsg(static_cast<const KDL::Frame&>(in));
  return msg;
}

inline
void fromMsg(const geometry_msgs::msg::PoseStamped& msg, tf2::Stamped<KDL::Frame>& out)
{
  out.stamp_ = tf2_ros::fromMsg(msg.header.stamp);
  out.frame_id_ = msg.header.frame_id;
  fromMsg(msg.pose, static_cast<KDL::Frame&>(out));
}

} // namespace

#endif // TF2_KDL_HPP