ros / geometry2

A set of ROS packages for keeping track of coordinate transforms.
190 stars 275 forks source link

[windows][melodic] Fix ambiguous call for tf2::convert on MSVC #444

Closed seanyen closed 4 years ago

seanyen commented 4 years ago

This is another attempt to rework - ambiguous call for tf2::convert on MSVC. Here is the previous attempt #367.

Problem

When building a downstream project (MoveIt), it fails to compile and reports 'tf2::fromMsg': ambiguous call to overloaded function.

wrap_python_move_group.cpp
D:\a\1\a\_ws\src\moveit\moveit_ros\planning_interface\py_bindings_tools\include\moveit/py_bindings_tools/serialize_msg.h(69): warning C4267: 'argument': conversion from 'size_t' to 'uint32_t', possible loss of data
D:\a\1\a\_ws\src\moveit\moveit_ros\planning_interface\move_group_interface\src\wrap_python_move_group.cpp(97): note: see reference to function template instantiation 'void moveit::py_bindings_tools::deserializeMsg<geometry_msgs::Pose>(const std::string &,T &)' being compiled
with
[
T=geometry_msgs::Pose
]
C:\opt\rosdeps\x64\include\boost-1_66\boost/bind/placeholders.hpp(54): note: see reference to class template instantiation 'boost::arg<9>' being compiled
C:\opt\rosdeps\x64\include\boost-1_66\boost/bind/placeholders.hpp(53): note: see reference to class template instantiation 'boost::arg<8>' being compiled
C:\opt\rosdeps\x64\include\boost-1_66\boost/bind/placeholders.hpp(52): note: see reference to class template instantiation 'boost::arg<7>' being compiled
C:\opt\rosdeps\x64\include\boost-1_66\boost/bind/placeholders.hpp(51): note: see reference to class template instantiation 'boost::arg<6>' being compiled
C:\opt\rosdeps\x64\include\boost-1_66\boost/bind/placeholders.hpp(50): note: see reference to class template instantiation 'boost::arg<5>' being compiled
C:\opt\rosdeps\x64\include\boost-1_66\boost/bind/placeholders.hpp(49): note: see reference to class template instantiation 'boost::arg<4>' being compiled
C:\opt\rosdeps\x64\include\boost-1_66\boost/bind/placeholders.hpp(48): note: see reference to class template instantiation 'boost::arg<3>' being compiled
C:\opt\rosdeps\x64\include\boost-1_66\boost/bind/placeholders.hpp(47): note: see reference to class template instantiation 'boost::arg<2>' being compiled
C:\opt\rosdeps\x64\include\boost-1_66\boost/bind/placeholders.hpp(46): note: see reference to class template instantiation 'boost::arg<1>' being compiled
D:\a\1\a\_ws\src\moveit\moveit_ros\planning_interface\py_bindings_tools\include\moveit/py_bindings_tools/serialize_msg.h(58): warning C4267: 'argument': conversion from 'size_t' to 'uint32_t', possible loss of data
D:\a\1\a\_ws\src\moveit\moveit_ros\planning_interface\move_group_interface\src\wrap_python_move_group.cpp(138): note: see reference to function template instantiation 'std::string moveit::py_bindings_tools::serializeMsg<moveit_msgs::RobotState>(const T &)' being compiled
with
[
T=moveit_msgs::RobotState
]
C:\opt\ros\melodic\x64\include\tf2/impl/convert.h(72): error C2668: 'tf2::fromMsg': ambiguous call to overloaded function

Resolution

For MSVC, it requires to be explicit on what's the namespace of the overloaded templated (and non-templated functions). On the flip side, for GCC\Clang, specifying the namespace requires the overloaded functions to be forward-declared and which would mean to shuffle the header inclusion by different order.

Making all the overloaded functions visible before tf2::impl::convert gets defined looks to me a more proper fix. However, given tf2 is a relatively fundamental package in ROS stack, I am hesitate to do much extensive header refactoring. So I am simply using compiler conditional guard to mitigate the build break (and added a test case to synthesize the MoveIt usage).

seanyen commented 4 years ago

@rhaschke Hi! I am trying to rework the ambiguous call problem for tf2::convert in MSVC. Can you try to see if this patch passes the clang build?

seanyen commented 4 years ago

@tfoote The CI fails at rosdep step: Is it an known issue for now?

RuntimeError: Could not resolve the rosdep key 'actionlib'
rhaschke commented 4 years ago

Can you try to see if this patch passes the clang build?

I guess you are referring to the MoveIt CI builds?

seanyen commented 4 years ago

I guess you are referring to the MoveIt CI builds?

Yes! I am trying to tackle this issue here: https://github.com/ros/rosdistro/pull/23469#issuecomment-576397569

rhaschke commented 4 years ago

Unfortunately, I don't have time to look into this right now. However, you could do it yourself: just prepare a PR against MoveIt, adding your tf2 repo to the rosinstall file. Travis should compile with your branch then. You can easily retrigger Travis by closing and reopening the PR. Please mark the PR as WIP, to emphasize that it is not intended for merging. Thanks for tackling the problem!

seanyen commented 4 years ago

Unfortunately, I don't have time to look into this right now. However, you could do it yourself: just prepare a PR against MoveIt, adding your tf2 repo to the rosinstall file. Travis should compile with your branch then. You can easily retrigger Travis by closing and reopening the PR. Please mark the PR as WIP, to emphasize that it is not intended for merging. Thanks for tackling the problem!

No problem! I will be trying the MoveIt Travis build.

gleichdick commented 4 years ago

Hey, nice to know that somebody else is tackling this issue :smile: I made a proposal in #433 which is backward-incompatible but independent of the header include order. To fix this in melodic, we could try to get rid of the templated forward-declarations of fromMsg and toMsg in <tf2/convert.h>. Then, tf2::convert() hopefully picks the correct (non-templated) overloads instead of the forward declaration. Note that AFAIK in this case all overloads have to be declared before tf2::convert() is used.

gleichdick commented 4 years ago

What about an explicit conversion in wrap_python_move_group.cpp?

--- a/moveit_ros/planning_interface/move_group_interface/src/wrap_python_move_group.cpp
+++ b/moveit_ros/planning_interface/move_group_interface/src/wrap_python_move_group.cpp
@@ -46,6 +46,8 @@
 #include <tf2_eigen/tf2_eigen.h>
 #include <tf2/LinearMath/Quaternion.h>
 #include <tf2_geometry_msgs/tf2_geometry_msgs.h>
+#include <tf2/convert.h>
+#include <geometry_msgs/Quaternion.h>
 #include <tf2_ros/buffer.h>

 #include <boost/python.hpp>
@@ -295,7 +297,10 @@ public:
           tf2::Quaternion tq;
           tq.setRPY(v[3], v[4], v[5]);
           Eigen::Quaterniond eq;
-          tf2::convert(tq, eq);
+          // three way convert is currently broken
+          geometry_msgs::Quaternion q_msg;
+          tf2::convert(t1, q_msg);
+          tf2::convert(q_msg, eq);
           p = Eigen::Isometry3d(eq);
         }
         else

This is of course only a workaround for the MSVC error message...

rhaschke commented 4 years ago

I would prefer, if you can come up with a solution that doesn't require to modify downstream projects. MoveIt is for sure only one out of many projects utilizing tf conversions.

seanyen commented 4 years ago

@tfoote @rhaschke @gleichdick This is ready for review and merge. I verified the change with the MoveIt CI too and it shows all green: https://travis-ci.com/seanyen/moveit/builds/148308643

The fix is probably not the optimal, but I think it comes with a very low risk to break the downstream project, especially for melodic release.

gleichdick commented 4 years ago

Thank you for your effort, but IMHO the issue is still not solved in general. To make this clear:

#include <iostream>
namespace msgs {
    struct A_msg { 
        A_msg(){} // for clang
    };
}

namespace datatypes {
    struct B_dt {};
}

namespace tf2 {
    template <class A, class B>
    void fromMsg(const A&, B&);

    template <class A, class B>
    void convert(const A& a, B& b) {
        fromMsg(a, b);
    }

    //template<>
    void fromMsg(const msgs::A_msg& a, datatypes::B_dt& b) {}
}

int main () {
    const msgs::A_msg a;
    datatypes::B_dt b;
    tf2::convert(a, b);
    std::cout << "Hello, world!\n";
}

When you try to compile this with gcc 7.4, gcc 9.2 or clang 9 this results in a linker error:

 clang++ -otest snippet.cpp 
/usr/bin/ld: /tmp/test_t-7ffbbd.o: in function `void tf2::convert<msgs::A_msg, datatypes::B_dt>(msgs::A_msg const&, datatypes::B_dt&)':
test_t.cpp:(.text._ZN3tf27convertIN4msgs5A_msgEN9datatypes4B_dtEEEvRKT_RT0_[_ZN3tf27convertIN4msgs5A_msgEN9datatypes4B_dtEEEvRKT_RT0_]+0x19): undefined reference to `void tf2::fromMsg<msgs::A_msg, datatypes::B_dt>(msgs::A_msg const&, datatypes::B_dt&)'

It somehow compiles fine with MSVC (tested on godbolt). If you uncomment the template<> statement, it compiles fine with gcc and clang.

TL; DR As I explained in #430, fromMsg()/toMsg are not template specializations (indicated with template<>) but traditional overloads. So either the forward declaration have to be removed (in convert.h) or all overloads have to become a template specialization (which breaks current downstream projects)

seanyen commented 4 years ago

@tfoote Friendly ping.

seanyen commented 4 years ago

@tfoote BTW, hope this can be cherry-picked to noetic-devel too.

seanyen commented 4 years ago

@tfoote Friendly ping.

tfoote commented 4 years ago

@ros-pull-request-builder retest this please