Skip to content

Commit ca47b56

Browse files
committed
[2/7] Complete rework: convert.h
1 parent 1f4b16e commit ca47b56

File tree

2 files changed

+692
-101
lines changed

2 files changed

+692
-101
lines changed

tf2/include/tf2/convert.h

Lines changed: 132 additions & 76 deletions
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,7 @@
2626
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
2727
// POSSIBILITY OF SUCH DAMAGE.
2828

29-
/** \author Tully Foote */
29+
/** \author Tully Foote, Bjarne von Horn */
3030

3131
#ifndef TF2__CONVERT_H_
3232
#define TF2__CONVERT_H_
@@ -35,79 +35,98 @@
3535
#include <array>
3636
#include <string>
3737

38-
#include "builtin_interfaces/msg/time.hpp"
39-
#include "geometry_msgs/msg/transform_stamped.hpp"
40-
#include "rosidl_runtime_cpp/traits.hpp"
41-
#include "tf2/exceptions.h"
42-
#include "tf2/impl/convert.h"
43-
#include "tf2/transform_datatypes.h"
44-
#include "tf2/visibility_control.h"
38+
#include <builtin_interfaces/msg/time.hpp>
39+
#include <geometry_msgs/msg/transform_stamped.hpp>
40+
#include <rosidl_runtime_cpp/traits.hpp>
41+
42+
43+
#include "exceptions.h"
44+
#include "impl/convert.h"
45+
#include "impl/stamped_traits.hpp"
46+
#include "time.h"
47+
#include "transform_datatypes.h"
48+
#include "visibility_control.h"
4549

4650
namespace tf2
4751
{
48-
49-
/**\brief The templated function expected to be able to do a transform
52+
/** \brief The templated function expected to be able to do a transform.
5053
*
5154
* This is the method which tf2 will use to try to apply a transform for any given datatype.
52-
* \param data_in[in] The data to be transformed.
53-
* \param data_out[inout] A reference to the output data. Note this can point to data in and the method should be mutation safe.
54-
* \param transform[in] The transform to apply to data_in to fill data_out.
55+
* \param[in] data_in The data to be transformed.
56+
* \param[in,out] data_out A reference to the output data.
57+
* Note this can point to data in and the method should be mutation safe.
58+
* \param[in] transform The transform to apply to data_in to fill data_out.
59+
* \tparam T The type of the data to be transformed.
5560
*
5661
* This method needs to be implemented by client library developers
5762
*/
5863
template<class T>
5964
void doTransform(
60-
const T & data_in, T & data_out,
61-
const geometry_msgs::msg::TransformStamped & transform);
62-
63-
/**\brief Get the timestamp from data
64-
* \param[in] t The data input.
65-
* \return The timestamp associated with the data.
66-
*/
67-
template<class T>
68-
tf2::TimePoint getTimestamp(const T & t);
65+
const T & data_in, T & data_out, const geometry_msgs::msg::TransformStamped & transform)
66+
{
67+
using TransformType = typename impl::DefaultTransformType<T>::type;
68+
TransformType t;
69+
tf2::fromMsg<>(transform.transform, t);
70+
data_out = t * data_in;
71+
}
6972

70-
/**\brief Get the frame_id from data
71-
* \param[in] t The data input.
72-
* \return The frame_id associated with the data.
73+
/** \brief The templated function expected to be able to do a transform.
74+
*
75+
* This is the method which tf2 will use to try to apply a transform for any given datatype.
76+
* Overload for tf2::Stamped\<T\> types,
77+
* uses doTransform(const T&, T&, const geometry_msgs::msg::TransformStamped&).
78+
* \param[in] data_in The data to be transformed.
79+
* \param[in,out] data_out A reference to the output data.
80+
* Note this can point to data in and the method should be mutation safe.
81+
* \param[in] transform The transform to apply to data_in to fill data_out.
82+
* \tparam T The type of the data to be transformed.
7383
*/
7484
template<class T>
75-
std::string getFrameId(const T & t);
85+
void doTransform(
86+
tf2::Stamped<T> const & data_in, tf2::Stamped<T> & data_out,
87+
const geometry_msgs::msg::TransformStamped & transform)
88+
{
89+
T tmp;
90+
doTransform(static_cast<const T &>(data_in), tmp, transform);
91+
data_out = tf2::Stamped<T>{tmp, transform.header.stamp, transform.header.frame_id};
92+
}
7693

77-
/**\brief Get the covariance matrix from data
94+
/**
95+
* \brief Get the timestamp from data
7896
* \param[in] t The data input.
79-
* \return The covariance matrix associated with the data.
97+
* \return The timestamp associated with the data.
8098
*/
8199
template<class T>
82-
std::array<std::array<double, 6>, 6> getCovarianceMatrix(const T & t);
100+
inline tf2::TimePoint getTimestamp(const T & t)
101+
{
102+
return impl::StampedAttributesHelper<T>::getTimestamp(t);
103+
}
83104

84-
/**\brief Get the frame_id from data
85-
*
86-
* An implementation for Stamped<P> datatypes.
87-
*
105+
/**
106+
* \brief Get the frame_id from data
88107
* \param[in] t The data input.
89108
* \return The frame_id associated with the data.
90109
*/
91-
template<class P>
92-
tf2::TimePoint getTimestamp(const tf2::Stamped<P> & t)
110+
template<class T>
111+
inline std::string getFrameId(const T & t)
93112
{
94-
return t.stamp_;
113+
return impl::StampedAttributesHelper<T>::getFrameId(t);
95114
}
96115

97-
/**\brief Get the frame_id from data
98-
*
99-
* An implementation for Stamped<P> datatypes.
100-
*
116+
/**
117+
* \brief Get the covariance matrix from data
101118
* \param[in] t The data input.
102-
* \return The frame_id associated with the data.
119+
* \return The covariance matrix associated with the data.
103120
*/
104-
template<class P>
105-
std::string getFrameId(const tf2::Stamped<P> & t)
121+
template<class T>
122+
std::array<std::array<double, 6>, 6> getCovarianceMatrix(const T & t)
106123
{
107-
return t.frame_id_;
124+
using traits = impl::StampedMessageTraits<T>;
125+
return covarianceRowMajorToNested(traits::getCovariance(t));
108126
}
109127

110-
/**\brief Get the covariance matrix from data
128+
/**
129+
* \brief Get the covariance matrix from data
111130
*
112131
* An implementation for WithCovarianceStamped<P> datatypes.
113132
*
@@ -120,53 +139,87 @@ std::array<std::array<double, 6>, 6> getCovarianceMatrix(const tf2::WithCovarian
120139
return t.cov_mat_;
121140
}
122141

123-
/**\brief Function that converts from one type to a ROS message type. It has to be
124-
* implemented by each data type in tf2_* (except ROS messages) as it is
125-
* used in the "convert" function.
126-
* \param a an object of whatever type
142+
/**
143+
* \brief Function that converts from one type to a ROS message type.
144+
*
145+
* The implementation of this function should be done in the tf2_* packages
146+
* for each datatypes. Preferably in a specialization of the impl::ConversionImplementation struct.
147+
* \param[in] a an object of whatever type
148+
* \tparam A Non-message Datatype
149+
* \tparam B ROS message Datatype.
150+
* The default value will be taken from impl::DefaultMessageForDatatype\<A\>::type.
127151
* \return the conversion as a ROS message
128152
*/
129153
template<typename A, typename B>
130-
B toMsg(const A & a);
154+
inline B toMsg(const A & a)
155+
{
156+
B b;
157+
impl::ConversionImplementation<A, B>::toMsg(a, b);
158+
return b;
159+
}
160+
161+
/**
162+
* \brief Function that converts from one type to a ROS message type.
163+
*
164+
* The implementation of this function should be done in the tf2_* packages
165+
* for each datatypes. Preferably in a specialization of the impl::ConversionImplementation struct.
166+
* \param[in] a an object of whatever type
167+
* \param[out] b ROS message
168+
* \tparam A Non-message Datatype
169+
* \tparam B Type of the ROS Message
170+
* \return Reference to the parameter b
171+
*/
172+
template<typename A, typename B>
173+
inline B & toMsg(const A & a, B & b)
174+
{
175+
impl::ConversionImplementation<A, B>::toMsg(a, b);
176+
return b;
177+
}
131178

132-
/**\brief Function that converts from a ROS message type to another type. It has to be
133-
* implemented by each data type in tf2_* (except ROS messages) as it is used
134-
* in the "convert" function.
135-
* \param a a ROS message to convert from
136-
* \param b the object to convert to
179+
/**
180+
* \brief Function that converts from a ROS message type to another type.
181+
*
182+
* The implementation of this function should be done in the tf2_* packages
183+
* for each datatypes. Preferably in a specialization of the impl::ConversionImplementation struct.
184+
* \param[in] a a ROS message to convert from
185+
* \param[out] b the object to convert to
186+
* \tparam A ROS message type
187+
* \tparam B Arbitrary type
137188
*/
138189
template<typename A, typename B>
139-
void fromMsg(const A &, B & b);
190+
inline void fromMsg(const A & a, B & b)
191+
{
192+
impl::ConversionImplementation<B, A>::fromMsg(a, b);
193+
}
140194

141-
/**\brief Function that converts any type to any type (messages or not).
195+
/**
196+
* \brief Function that converts any type to any type (messages or not).
197+
*
142198
* Matching toMsg and from Msg conversion functions need to exist.
143199
* If they don't exist or do not apply (for example, if your two
144200
* classes are ROS messages), just write a specialization of the function.
145-
* \param a an object to convert from
146-
* \param b the object to convert to
201+
* \param[in] a an object to convert from
202+
* \param[in,out] b the object to convert to
203+
* \tparam A Type of the object to convert from
204+
* \tparam B Type of the object to convert to
147205
*/
148206
template<class A, class B>
149-
void convert(const A & a, B & b)
150-
{
151-
impl::Converter<rosidl_generator_traits::is_message<A>::value,
152-
rosidl_generator_traits::is_message<B>::value>::convert(a, b);
153-
}
154-
155-
template<class A>
156-
void convert(const A & a1, A & a2)
207+
inline void convert(const A & a, B & b)
157208
{
158-
if (&a1 != &a2) {
159-
a2 = a1;
160-
}
209+
impl::Converter<
210+
rosidl_generator_traits::is_message<A>::value,
211+
rosidl_generator_traits::is_message<B>::value, A, B>::convert(a, b);
161212
}
162213

163-
/**\brief Function that converts from a row-major representation of a 6x6
214+
/** \brief Function that converts from a row-major representation of a 6x6
164215
* covariance matrix to a nested array representation.
165-
* \param row_major A row-major array of 36 covariance values.
216+
* \param[in] row_major A row-major array of 36 covariance values.
166217
* \return A nested array representation of 6x6 covariance values.
167218
*/
168219
inline
169-
std::array<std::array<double, 6>, 6> covarianceRowMajorToNested(const std::array<double, 36> & row_major)
220+
std::array<std::array<double, 6>, 6> covarianceRowMajorToNested(
221+
const std::array<double,
222+
36> & row_major)
170223
{
171224
std::array<std::array<double, 6>, 6> nested_array;
172225
std::array<double, 36>::const_iterator ss = row_major.begin();
@@ -177,13 +230,16 @@ std::array<std::array<double, 6>, 6> covarianceRowMajorToNested(const std::array
177230
return nested_array;
178231
}
179232

180-
/**\brief Function that converts from a nested array representation of a 6x6
233+
/**
234+
* \brief Function that converts from a nested array representation of a 6x6
181235
* covariance matrix to a row-major representation.
182-
* \param nested_array A nested array representation of 6x6 covariance values.
236+
* \param[in] nested_array A nested array representation of 6x6 covariance values.
183237
* \return A row-major array of 36 covariance values.
184238
*/
185239
inline
186-
std::array<double, 36> covarianceNestedToRowMajor(const std::array<std::array<double, 6>, 6> & nested_array)
240+
std::array<double, 36> covarianceNestedToRowMajor(
241+
const std::array<std::array<double, 6>,
242+
6> & nested_array)
187243
{
188244
std::array<double, 36> row_major = {};
189245
size_t counter = 0;

0 commit comments

Comments
 (0)