Nodelet: symbol lookup error, undefined symbol.
Hi, I want to receive an Octree (via the octomap server) and given the size of the data being transferred, I changed all of my code from node to nodelet.
A snippet of the resulting header is shown below:
namespace nodelet_obstacle_detector
{
using octomap_msgs::GetOctomap;
using namespace std;
using namespace fcl;
class OD : public nodelet::Nodelet
{
public:
OD();
protected:
virtual void onInit();
ros::NodeHandle nh;
ros::Subscriber odom_sub;
//Octomap Service
GetOctomap::Request req;
GetOctomap::Response resp;
std::string serv_name;
// //Octomap Objects
octomap::AbstractOcTree* msg_octree;
fcl::OcTree* tree_fcl;
And the .cpp is also shown:
namespace nodelet_obstacle_detector
{
OD::OD(){}
void OD::onInit()
{
nh = getPrivateNodeHandle();
NODELET_DEBUG("Initialized the Nodelet (OD)");
serv_name = "/octomap_binary";
odom_sub = nh.subscribe("/base_odometry/odom", 1, &OD::odomCallback, this);
}
void OD::odomCallback(const nav_msgs::Odometry::ConstPtr &odom_msg)
{
OD::processingOctree();
}
void OD::processingOctree()
{
if (nh.ok()) {
octomap::OcTree* octree = NULL;
while((ros::ok() && !ros::service::call(serv_name, req, resp)) || resp.map.data.size()==0)
{
NODELET_INFO("Request to octomap failed; trying again.");
usleep(1000000);
}
msg_octree = octomap_msgs::msgToMap(resp.map);
if (msg_octree)
octree = dynamic_cast<octomap::OcTree*>(msg_octree);
if (octree)
{
res = octree->getResolution();
tree_fcl = (new fcl::OcTree(shared_ptr<const octomap::OcTree>(octree)));
}
The code compiles and executes, although, it crashes once Octomap is received, due to the last line of code:
tree_fcl = (new fcl::OcTree(shared_ptr<const octomap::OcTree>(octree)));
Without that line, the code runs ok, so I now that the problem is there. The error that appears is the following:
/opt/ros/kinetic/lib/nodelet/nodelet: symbol lookup error: /home/hh/ros_ws/devel/lib//libuav.so: undefined symbol: _ZN3fcl4AABBC1Ev
[standalone_nodelet-3] process has died [pid 4544, exit code 127, cmd /opt/ros/kinetic/lib/nodelet/nodelet manager__name:=standalone_nodelet __log:=/home/hh/.ros/log/b3622254-8efa-11e8-aecf-b8ee65da891a/standalone_nodelet-3.log].
log file: /home/hh/.ros/log/b3622254-8efa-11e8-aecf-b8ee65da891a/standalone_nodelet-3*.log
From here, I did:
$ nm -D /home/hh/ros_ws/devel/lib//libuav.so | grep _ZN3fcl4AABBC1Ev
U _ZN3fcl4AABBC1Ev
Also, I did:
$ c++filt _ZN3fcl4AABBC1Ev
fcl::AABB::AABB()
And to find out if it was defined, I did:
$ grep "AABB()" . -rnw
./src/fcl/include/fcl/BV/AABB.h:57: AABB();
./src/fcl/src/BV/AABB.cpp:46:AABB::AABB() : min_(std::numeric_limits<FCL_REAL>::max()),
Which shows that the missing symbol does exist, right?
As this code was tested and fully working as a node, I don't understand why it is not working as nodelet and can't figure it out. I have also removed the build and devel folders and recompiled it, but it did not solve it.
Any hint would be appreciated. Thank you!
Asked by jpde.lopes on 2018-07-23 23:58:11 UTC
Comments