Skip to content
This repository was archived by the owner on May 31, 2025. It is now read-only.

Conversation

@seanyen
Copy link
Contributor

@seanyen seanyen commented Feb 8, 2020

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 seanyen closed this Feb 9, 2020
@seanyen seanyen reopened this Feb 9, 2020
@seanyen
Copy link
Contributor Author

seanyen commented Feb 9, 2020

@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
Copy link
Contributor Author

seanyen commented Feb 9, 2020

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

RuntimeError: Could not resolve the rosdep key 'actionlib'

@rhaschke
Copy link
Contributor

rhaschke commented Feb 9, 2020

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

I guess you are referring to the MoveIt CI builds?

@seanyen
Copy link
Contributor Author

seanyen commented Feb 9, 2020

I guess you are referring to the MoveIt CI builds?

Yes! I am trying to tackle this issue here: ros/rosdistro#23469 (comment)

@rhaschke
Copy link
Contributor

rhaschke commented Feb 9, 2020

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
Copy link
Contributor Author

seanyen commented Feb 9, 2020

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
Copy link

Hey, nice to know that somebody else is tackling this issue 😄
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
Copy link

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
Copy link
Contributor

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 seanyen marked this pull request as ready for review February 11, 2020 04:07
@seanyen
Copy link
Contributor Author

seanyen commented Feb 11, 2020

@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
Copy link

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
Copy link
Contributor Author

seanyen commented Feb 26, 2020

@tfoote Friendly ping.

@seanyen
Copy link
Contributor Author

seanyen commented Mar 25, 2020

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

@tfoote tfoote self-requested a review March 26, 2020 20:53
inline void Converter<false, false>::convert(const A& a, B& b)
{
#ifdef _MSC_VER
tf2::fromMsg(tf2::toMsg(a), b);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Is it not safe to use this more qualified name ouside of MSVC so we could save the ifdef?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

As I recalled, it caused compilation errors in GCC\Clang settings but let me test and spin a CI to make sure.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@tfoote Here is the error that if I use this full qualified name. It seems that GCC is okay with a unresolved (yet) function name referenced in the template code, but doesn't like the case where you reference it in the fully qualified form.

15:39:27 [  9%] Building CXX object CMakeFiles/tf2_ros.dir/src/buffer.cpp.o
15:39:31 In file included from /tmp/ws/install_isolated/include/tf2/convert.h:39:0,
15:39:31                  from /tmp/ws/src/geometry2/tf2_ros/include/tf2_ros/buffer_interface.h:40,
15:39:31                  from /tmp/ws/src/geometry2/tf2_ros/include/tf2_ros/buffer.h:35,
15:39:31                  from /tmp/ws/src/geometry2/tf2_ros/src/buffer.cpp:33:
15:39:31 /tmp/ws/install_isolated/include/tf2/impl/convert.h: In static member function ‘static void tf2::impl::Converter<IS_MESSAGE_A, IS_MESSAGE_B>::convert(const A&, B&) [with A = A; B = B; bool IS_MESSAGE_A = true; bool IS_MESSAGE_B = false]’:
15:39:31 /tmp/ws/install_isolated/include/tf2/impl/convert.h:58:8: error: ‘fromMsg’ is not a member of ‘tf2’
15:39:31    tf2::fromMsg(a, b);
15:39:31         ^~~~~~~
15:39:31 /tmp/ws/install_isolated/include/tf2/impl/convert.h: In static member function ‘static void tf2::impl::Converter<IS_MESSAGE_A, IS_MESSAGE_B>::convert(const A&, B&) [with A = A; B = B; bool IS_MESSAGE_A = false; bool IS_MESSAGE_B = true]’:
15:39:31 /tmp/ws/install_isolated/include/tf2/impl/convert.h:65:12: error: ‘toMsg’ is not a member of ‘tf2’
15:39:31    b = tf2::toMsg(a);
15:39:31             ^~~~~
15:39:31 /tmp/ws/install_isolated/include/tf2/impl/convert.h: In static member function ‘static void tf2::impl::Converter<IS_MESSAGE_A, IS_MESSAGE_B>::convert(const A&, B&) [with A = A; B = B; bool IS_MESSAGE_A = false; bool IS_MESSAGE_B = false]’:
15:39:31 /tmp/ws/install_isolated/include/tf2/impl/convert.h:72:8: error: ‘fromMsg’ is not a member of ‘tf2’
15:39:31    tf2::fromMsg(tf2::toMsg(a), b);
15:39:31         ^~~~~~~
15:39:31 /tmp/ws/install_isolated/include/tf2/impl/convert.h:72:21: error: ‘toMsg’ is not a member of ‘tf2’
15:39:31    tf2::fromMsg(tf2::toMsg(a), b);
15:39:31                      ^~~~~
15:39:31 CMakeFiles/tf2_ros.dir/build.make:62: recipe for target 'CMakeFiles/tf2_ros.dir/src/buffer.cpp.o' failed
15:39:31 make[2]: *** [CMakeFiles/tf2_ros.dir/src/buffer.cpp.o] Error 1
15:39:31 CMakeFiles/Makefile2:248: recipe for target 'CMakeFiles/tf2_ros.dir/all' failed
15:39:31 make[1]: *** [CMakeFiles/tf2_ros.dir/all] Error 2
15:39:31 Makefile:140: recipe for target 'all' failed
15:39:31 make: *** [all] Error 2
15:39:31 <== Failed to process package 'tf2_ros': 

@seanyen
Copy link
Contributor Author

seanyen commented Apr 26, 2020

@tfoote Friendly ping.

@tfoote
Copy link
Member

tfoote commented May 13, 2020

@ros-pull-request-builder retest this please

@tfoote tfoote merged commit 9b8022c into ros:melodic-devel May 13, 2020
tfoote pushed a commit that referenced this pull request May 13, 2020
rhaschke pushed a commit to rhaschke/geometry2 that referenced this pull request Jun 30, 2020
tfoote added a commit that referenced this pull request Aug 24, 2020
* Revert "rework Eigen functions namespace hack" (#436)

* Fixed warnings in message_filter.h (#434)

the variables are not used in function body and caused -Wunused-parameter to trigger with -Wall

* Fix ambiguous call for tf2::convert on MSVC (#444)

* rework ambiguous call on MSVC.

Co-authored-by: Tully Foote <[email protected]>
Co-authored-by: moooeeeep <[email protected]>
Co-authored-by: Sean Yen <[email protected]>
Sign up for free to subscribe to this conversation on GitHub. Already have an account? Sign in.

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

4 participants