tf2 Namespace Reference

tf2 Namespace Reference#

Beluga ROS: tf2 Namespace Reference
Beluga ROS
tf2 Namespace Reference

tf2 namespace extension for message conversion overload resolution. More...

Functions

template<class Scalar >
beluga_ros::msg::Point toMsg (const Eigen::Matrix< Scalar, 2, 1 > &in)
 Converts an Eigen Vector2 type to a Point message. More...
 
template<class Scalar >
beluga_ros::msg::Pose & toMsg (const Sophus::SE2< Scalar > &in, beluga_ros::msg::Pose &out)
 Converts a Sophus SE2 type to a Pose message. More...
 
template<class Scalar >
beluga_ros::msg::Pose & toMsg (const Sophus::SE3< Scalar > &in, beluga_ros::msg::Pose &out)
 Converts a Sophus SE3 type to a Pose message. More...
 
template<class Scalar >
beluga_ros::msg::Transform toMsg (const Sophus::SE2< Scalar > &in)
 Converts a Sophus SE2 type to a Transform message. More...
 
template<class Scalar >
beluga_ros::msg::Transform toMsg (const Sophus::SE3< Scalar > &in)
 Converts a Sophus SE3 type to a Transform message. More...
 
template<class Scalar >
void fromMsg (const beluga_ros::msg::Transform &msg, Sophus::SE2< Scalar > &out)
 Converts a Transform message type to a Sophus SE2 type. More...
 
template<class Scalar >
void fromMsg (const beluga_ros::msg::Transform &msg, Sophus::SE3< Scalar > &out)
 Converts a Transform message type to a Sophus SE3 type. More...
 
template<class Scalar >
void fromMsg (const beluga_ros::msg::Pose &msg, Sophus::SE2< Scalar > &out)
 Converts a Pose message type to a Sophus SE2 type. More...
 
template<class Scalar >
void fromMsg (const beluga_ros::msg::Pose &msg, Sophus::SE3< Scalar > &out)
 Converts a Pose message type to a Sophus SE3 type. More...
 
template<template< typename, std::size_t > class Array, typename Scalar >
Array< Scalar, 36 > & covarianceEigenToRowMajor (const Sophus::Matrix3< Scalar > &in, Array< Scalar, 36 > &out)
 Converts a Sophus (ie. Eigen) 3x3 covariance matrix to a 6x6 row-major array. More...
 
template<template< typename, std::size_t > class Array, typename Scalar >
Sophus::Matrix3< Scalar > & covarianceRowMajorToEigen (const Array< Scalar, 36 > &in, Sophus::Matrix3< Scalar > &out)
 Converts a 6x6 row-major array to an Eigen 3x3 covariance matrix. More...
 
template<typename Scalar >
beluga_ros::msg::PoseWithCovariance toMsg (const Sophus::SE3< Scalar > &in, const Eigen::Matrix< Scalar, 6, 6 > &covariance)
 

Detailed Description

tf2 namespace extension for message conversion overload resolution.

Function Documentation

◆ covarianceEigenToRowMajor()

template<template< typename, std::size_t > class Array, typename Scalar >
Array<Scalar, 36>& tf2::covarianceEigenToRowMajor ( const Sophus::Matrix3< Scalar > &  in,
Array< Scalar, 36 > &  out 
)
inline

Converts a Sophus (ie. Eigen) 3x3 covariance matrix to a 6x6 row-major array.

Parameters
inA Sophus (ie. Eigen) 3x3 covariance matrix of a 2D pose (x, y, yaw).
outA row-major array of 36 covariance values of a 3D pose.
Returns
a reference to out.

◆ covarianceRowMajorToEigen()

template<template< typename, std::size_t > class Array, typename Scalar >
Sophus::Matrix3<Scalar>& tf2::covarianceRowMajorToEigen ( const Array< Scalar, 36 > &  in,
Sophus::Matrix3< Scalar > &  out 
)
inline

Converts a 6x6 row-major array to an Eigen 3x3 covariance matrix.

Parameters
inA row-major array of 36 covariance values of a 3D pose.
outA Sophus (ie. Eigen) 3x3 covariance matrix of a 2D pose (x, y, yaw).
Returns
A Sophus (ie. Eigen) 3x3 covariance matrix of a 2D pose (x, y, yaw).

◆ fromMsg() [1/4]

template<class Scalar >
void tf2::fromMsg ( const beluga_ros::msg::Pose &  msg,
Sophus::SE2< Scalar > &  out 
)
inline

Converts a Pose message type to a Sophus SE2 type.

This function is a specialization of the fromMsg template defined in tf2/convert.h.

Parameters
msgThe pose message to convert.
outThe pose converted to a Sophus SE2 element.

◆ fromMsg() [2/4]

template<class Scalar >
void tf2::fromMsg ( const beluga_ros::msg::Pose &  msg,
Sophus::SE3< Scalar > &  out 
)
inline

Converts a Pose message type to a Sophus SE3 type.

This function is a specialization of the fromMsg template defined in tf2/convert.h.

Parameters
msgThe pose message to convert.
outThe pose converted to a Sophus SE3 element.

◆ fromMsg() [3/4]

template<class Scalar >
void tf2::fromMsg ( const beluga_ros::msg::Transform &  msg,
Sophus::SE2< Scalar > &  out 
)
inline

Converts a Transform message type to a Sophus SE2 type.

This function is a specialization of the fromMsg template defined in tf2/convert.h.

Parameters
msgThe transform message to convert.
outThe transform converted to a Sophus SE2 element.

◆ fromMsg() [4/4]

template<class Scalar >
void tf2::fromMsg ( const beluga_ros::msg::Transform &  msg,
Sophus::SE3< Scalar > &  out 
)
inline

Converts a Transform message type to a Sophus SE3 type.

This function is a specialization of the fromMsg template defined in tf2/convert.h.

Parameters
msgThe transform message to convert.
outThe transform converted to a Sophus SE3 element.

◆ toMsg() [1/6]

template<class Scalar >
beluga_ros::msg::Point tf2::toMsg ( const Eigen::Matrix< Scalar, 2, 1 > &  in)
inline

Converts an Eigen Vector2 type to a Point message.

Parameters
inThe Eigen Vector2 element to convert.
Returns
The converted Point message.

◆ toMsg() [2/6]

template<class Scalar >
beluga_ros::msg::Transform tf2::toMsg ( const Sophus::SE2< Scalar > &  in)
inline

Converts a Sophus SE2 type to a Transform message.

This function is a specialization of the toMsg template defined in tf2/convert.h.

Parameters
inThe Sophus SE2 element to convert.
Returns
The transform converted to a Transform message.

◆ toMsg() [3/6]

template<class Scalar >
beluga_ros::msg::Pose& tf2::toMsg ( const Sophus::SE2< Scalar > &  in,
beluga_ros::msg::Pose &  out 
)
inline

Converts a Sophus SE2 type to a Pose message.

The canonical message for an SE2 instance is Transform. If a Pose message is needed, this function must be called directly using tf2::toMsg, not through the tf2::convert customization function.

Parameters
inThe Sophus SE2 element to convert.
outThe pose converted to a Pose message.
Returns
The pose converted to a Pose message.

◆ toMsg() [4/6]

template<class Scalar >
beluga_ros::msg::Transform tf2::toMsg ( const Sophus::SE3< Scalar > &  in)
inline

Converts a Sophus SE3 type to a Transform message.

This function is a specialization of the toMsg template defined in tf2/convert.h.

Parameters
inThe Sophus SE3 element to convert.
Returns
The transform converted to a Transform message.

◆ toMsg() [5/6]

template<class Scalar >
beluga_ros::msg::Pose& tf2::toMsg ( const Sophus::SE3< Scalar > &  in,
beluga_ros::msg::Pose &  out 
)
inline

Converts a Sophus SE3 type to a Pose message.

The canonical message for an SE3 instance is Transform. If a Pose message is needed, this function must be called directly using tf2::toMsg, not through the tf2::convert customization function.

Parameters
inThe Sophus SE3 element to convert.
outThe pose converted to a Pose message.
Returns
The pose converted to a Pose message.

◆ toMsg() [6/6]

template<typename Scalar >
beluga_ros::msg::PoseWithCovariance tf2::toMsg ( const Sophus::SE3< Scalar > &  in,
const Eigen::Matrix< Scalar, 6, 6 > &  covariance 
)
inline

Converts an SE3 pose and its covariance to a ROS message. NOTE: Input covariance is expected to use tangent space parametrization, consistent with the one in beluga's estimation libraries.