I build moveit and geometry2 from source, importing moveit_commander python module throws an ImportError due to missing symbol. See moveit/moveit#1785. Reverting #367 fixes the issue.
With HEAD pointed to cd55e45, following snippet (extracted from here) builds fine:
#include <tf2/LinearMath/Quaternion.h>
#include <Eigen/Geometry>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <tf2_eigen/tf2_eigen.h>
#include <iostream>
int main() {
Eigen::Quaterniond eq;
const tf2::Quaternion tq(0,1,0,1);
tf2::convert(tq, eq);
std::cout << eq.toRotationMatrix() << '\n';
}
With current melodic-devel (#367 applied, 1cbda1e), the symbol is also missing:
$ g++ -I/usr/include/eigen3/ -I/ws_moveit/install/include/ -I/opt/ros/melodic/include/ test.cpp
/tmp/ccQipwpW.o: In function `void tf2::impl::Converter<false, false>::convert<tf2::Quaternion, Eigen::Quaternion<double, 0> >(tf2::Quaternion const&, Eigen::Quaternion<double, 0>&)':
test.cpp:(.text._ZN3tf24impl9ConverterILb0ELb0EE7convertINS_10QuaternionEN5Eigen10QuaternionIdLi0EEEEEvRKT_RT0_[_ZN3tf24impl9ConverterILb0ELb0EE7convertINS_10QuaternionEN5Eigen10QuaternionIdLi0EEEEEvRKT_RT0_]+0x41): 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>&)'
collect2: error: ld returned 1 exit status
The function is declared in tf2_geometry_msgs.h as inline, but not template<>. If I got it right, the declaration order is:
template<class A, class B> fromMsg(const A&, B&);
template<class A, class B> void convert(const A&, B&) {...}
inline void fromMsg(const geometry_msgs::Quaternion &, tf2::Quaternion&) {...}
So, in impl::convert the correct overload is not found because it is defined as a stand-alone function afterwards (I guess).
When template<> is added to the fromMsg overloads, the snippet compiles.