ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Gazebo: undefined symbol: _ZTIN6gazebo12CameraPluginE when creating camera plugin

asked 2012-06-02 03:52:49 -0500

Saphrosit gravatar image

updated 2014-01-28 17:12:32 -0500

ngrennan gravatar image

I am trying to create a camera plugin in gazebo 1.0.1. I am using Ubuntu 12.04 on VMWare (MacOS Lion).
I don't know if I did all the steps in the correct way, so let me summarize:

I installed fuerte using the official instructions. I then followed both the instructions on ROS and Gazebo webpage to create plugins. I had no problems in creating a simple helloworld plugin or a plugin to move a box.

I am referring to this tutorial about the creation of a camera.

I created a package using

roscreate-pkg camera_plugin gazebo roscpp std_msgs

then I copy-paste the suggested code in two different files put in src/ folder of my package. I edited CMakeLists.txt in order to compile the plugins:

cmake_minimum_required(VERSION 2.4.6)
include($ENV{ROS_ROOT}/core/rosbuild/rosbuild.cmake)

rosbuild_init()

set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin)
set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib)

rosbuild_add_library(CameraDump SHARED src/CameraDump.cpp)
target_link_libraries(CameraDumb ${GAZEBO_libraries})

rosbuild_add_library(CameraMove SHARED src/CameraMove.cpp)
target_link_libraries(CameraMove ${GAZEBO_libraries} CameraPlugin)`

I compiled the code using rosmake, then I edited the default empty.world (after creating a backup copy) in order to add my plugins. I copy-paste the world suggested by the tutorial, then I launched gazebo using

roslaunch gazebo_worlds empty_world.launch.

Gazebo starts but I get as error:

Error [Plugin.hh:100] Failed to load plugin /path/camera_plugin/lib/libCameraDump.so: /path/camera_plugin/lib/libCameraDump.so: undefined symbol: _ZTIN6gazebo12CameraPluginE

Any suggestion on what may be the cause of this error?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
2

answered 2012-06-12 22:33:51 -0500

schadlerm gravatar image

I had a similar issue and have actually been periodically checking this page for a solution. However, I believe I have solved the issue (at least on my local machine).

The issue was an undefined symbol, thus pointing the error in the direction of the linking stage. Then I realized it was because I was not linking the correct libraries. It appears in your CMakeLists.txt above you have also made the same copy/paste mistake.

The CameraPlugin library should be linked with CameraDump, not CameraMove. Thus if you update your target_link_libraries as below it may fix the issue.

target_link_libraries(CameraDump ${GAZEBO_libraries} CameraPlugin)
target_link_libraries(CameraMove ${GAZEBO_libraries})
edit flag offensive delete link more

Question Tools

Stats

Asked: 2012-06-02 03:52:49 -0500

Seen: 2,044 times

Last updated: Jun 12 '12