-
Notifications
You must be signed in to change notification settings - Fork 280
[windows][melodic] Fix ambiguous call for tf2::convert on MSVC #444
Conversation
|
@rhaschke Hi! I am trying to rework the ambiguous call problem for |
|
@tfoote The CI fails at |
I guess you are referring to the MoveIt CI builds? |
Yes! I am trying to tackle this issue here: ros/rosdistro#23469 (comment) |
|
Unfortunately, I don't have time to look into this right now. |
No problem! I will be trying the MoveIt Travis build. |
|
Hey, nice to know that somebody else is tackling this issue 😄 |
|
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);
}
elseThis is of course only a workaround for the MSVC error message... |
|
I would prefer, if you can come up with a solution that doesn't require to modify downstream projects. |
5072c57 to
5fff918
Compare
|
@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 |
|
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: It somehow compiles fine with MSVC (tested on godbolt). If you uncomment the TL; DR As I explained in #430, |
5fff918 to
4b5d5e4
Compare
|
@tfoote Friendly ping. |
|
@tfoote BTW, hope this can be cherry-picked to |
| inline void Converter<false, false>::convert(const A& a, B& b) | ||
| { | ||
| #ifdef _MSC_VER | ||
| tf2::fromMsg(tf2::toMsg(a), b); |
There was a problem hiding this comment.
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?
There was a problem hiding this comment.
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.
There was a problem hiding this comment.
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':
|
@tfoote Friendly ping. |
|
@ros-pull-request-builder retest this please |
* rework ambiguous call on MSVC.
* rework ambiguous call on MSVC.
* 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]>
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.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::convertgets defined looks to me a more proper fix. However, giventf2is 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).