geometry2
geometry2 copied to clipboard
Change signature of tf2::fromMsg() and tf2::toMsg() to prevent linking errors.
Feature request
Make all overloads of fromMsg()
and toMsg()
template specializations (with template<>
)
Feature description
As pointed out in ros/geometry2#430, the fromMsg()
and toMsg()
Methods are traditional overloads (same function name, different arguments) and not a specialization of the templated forward declarations in <tf2/convert.h>
. So, sometimes the compiler chooses the wrong functions which results in linking errors like (from ros/geometry2#430):
undefined reference to `void tf2::fromMsg<geometry_msgs::Quaternion_<std::allocator<void> >, Eigen::Quaternion<double, 0> >(geometry_msgs::Quaternion_<std::allocator<void> > const&, Eigen::Quaternion<double, 0>&)'
Implementation considerations
I already made a PR on the ROS1 version (ros/geometry2#433) which declares all fromMsg()
and toMsg()
as template specializations. The conversion between two non-geometry-msgs types is done explicitly, the mappings are generated with the help of a python script. Implicitly mapping these types together does not work with template specializations.
Downstream projects will break, because tf2::toMsg()
now has two parameters in my implementation. Otherwise, the second type couldn't be deduced as the return value does not take part in template parameter deduction. On the other hand, all calls to tf2::fromMsg()
and tf2::convert()
will be fine.
Related Issues/PRs
ros/geometry2#430 ros/geometry2#433 ros/geometry2#367 ros/geometry2#444 ros-planning/moveit#1785
There are a few problems with this proposal:
- We've tried to do something like this in the past, and it led to a lot of downstream breakage (as you might imagine). This doesn't automatically disqualify it, but I'd like to use that experience to know what we are getting ourselves into.
- Looking at https://github.com/ros/geometry2/pull/433, I have to say that the API is strictly worse. Having to first define the message and then pass it as a ref parameter to
toMsg
is pretty ugly, and we'll get a lot of complaints from downstream consumers. Is there anything else we can do here to make the API nicer, even if we have to (further) break it?
The following idea came to my mind:
- create a templated struct which will contain a message type member for each non-message type
- make this the default argument for the second template parameter of
toMsg()
- move the actual conversion between message and non-message types into static struct member functions
With this approach, missing #includes
are caught at compile-time (because the struct converter
is empty).
The API is left unchanged, but the ABI will break (due to name mangling). Deprecating the non-templated functions does not work, as their precendence at overload resolution is higher than the (new) templated ones.
I'm happy to dig a bit deeper and to adapt my previous PR (ros/geometry2#433) if you agree to this approach.
Example:
// some arbitrary (non-)message datatypes
namespace msg
{
struct Vector3
{
double x, y, z;
};
} // namespace msg
namespace Eigen
{
struct Vector3d
{
double x, y, z;
};
} // namespace Eigen
// goes into tf2/convert.h
namespace tf2
{
// struct for 1.
template <class T>
struct default_msg_type
{
// empty on purpose
};
// struct for 3.
template <class T, class Msg>
struct converter_impl
{
// empty on purpose
};
template <typename T, typename Msg = typename default_msg_type<T>::type>
Msg toMsg(const T& t)
{
return converter_impl<T, Msg>::to_msg(t);
}
} // namespace tf2
// goes into tf2_eigen.h
namespace tf2
{
template <>
struct default_msg_type<Eigen::Vector3d>
{
using type = msg::Vector3;
};
template <>
struct converter_impl<Eigen::Vector3d, msg::Vector3>
{
static msg::Vector3 to_msg(const Eigen::Vector3d& v)
{
return msg::Vector3{ v.x, v.y, v.z };
}
};
} // namespace tf2
For the records, the new PR for ROS1: ros/geometry2#491