33#ifndef TF2__CONVERT_HPP_
34#define TF2__CONVERT_HPP_
40#include "geometry_msgs/msg/transform_stamped.hpp"
41#include "rosidl_runtime_cpp/traits.hpp"
61 const T & data_in, T & data_out,
62 const geometry_msgs::msg::TransformStamped & transform);
130template<
typename A,
typename B>
139template<
typename A,
typename B>
149template<
class A,
class B>
153 rosidl_generator_traits::is_message<B>::value>
::convert(a, b);
171 const std::array<double, 36> & row_major)
173 std::array<std::array<double, 6>, 6> nested_array;
174 std::array<double, 36>::const_iterator ss = row_major.begin();
175 for (std::array<double, 6> & dd : nested_array) {
176 std::copy_n(ss, dd.size(), dd.begin());
189 const std::array<std::array<double, 6>, 6> & nested_array)
191 std::array<double, 36> row_major = {};
193 for (
const auto & arr : nested_array) {
194 for (
const double & val : arr) {
195 row_major[counter] = val;
The data type which will be cross compatable with geometry_msgs This is the tf2 datatype equivilant o...
Definition transform_datatypes.hpp:49
TimePoint stamp_
The timestamp associated with this data.
Definition transform_datatypes.hpp:51
std::string frame_id_
The frame_id associated this data.
Definition transform_datatypes.hpp:52
The data type which will be cross compatable with geometry_msgs This is the tf2 datatype equivalent o...
Definition transform_datatypes.hpp:98
std::array< std::array< double, 6 >, 6 > cov_mat_
The covariance matrix associated with this data // NOLINT.
Definition transform_datatypes.hpp:102
Definition convert.hpp:39
Definition buffer_core.hpp:58
std::array< std::array< double, 6 >, 6 > covarianceRowMajorToNested(const std::array< double, 36 > &row_major)
Function that converts from a row-major representation of a 6x6 covariance matrix to a nested array r...
Definition convert.hpp:170
std::array< double, 36 > covarianceNestedToRowMajor(const std::array< std::array< double, 6 >, 6 > &nested_array)
Function that converts from a nested array representation of a 6x6 covariance matrix to a row-major r...
Definition convert.hpp:188
void doTransform(const T &data_in, T &data_out, const geometry_msgs::msg::TransformStamped &transform)
The templated function expected to be able to do a transform.
B toMsg(const A &a)
Function that converts from one type to a ROS message type. It has to be implemented by each data typ...
std::string getFrameId(const T &t)
Get the frame_id from data.
tf2::TimePoint getTimestamp(const T &t)
Get the timestamp from data.
std::chrono::time_point< std::chrono::system_clock, Duration > TimePoint
Definition time.hpp:41
void fromMsg(const A &a, B &b)
Function that converts from a ROS message type to another type. It has to be implemented by each data...
std::array< std::array< double, 6 >, 6 > getCovarianceMatrix(const T &t)
Get the covariance matrix from data.
void convert(const A &a, B &b)
Function that converts any type to any type (messages or not). Matching toMsg and from Msg conversion...
Definition convert.hpp:150