Cannot call function "rendering::Scene::VisualAt", undefined symbol?
Whenever I call the function "rendering::Scene::VisualAt" or "Camera::ZValue", it complains:
gzserver: symbol lookup error:
catkin_ws/devel/lib/librand_camera.so:
undefined symbol: _ZN6gazebo9rendering6Camera6ZValueEii
in which "rand_camera" is the my project name. Anyone knows how to solve this? I really appreciate it!!
------------------- Details---------------------
Gazebo version: 7.1
CMakeLists:
cmake_minimum_required(VERSION 2.8.3)
project(rand_camera)
find_package(catkin REQUIRED COMPONENTS
gazebo
gazebo_dev
roslib
roscpp
geometry_msgs
std_srvs
std_msgs
gazebo_msgs
gazebo_ext_msgs
gazebo_plugins
)
find_package(OpenCV REQUIRED)
find_package(Boost REQUIRED COMPONENTS thread)
catkin_package(
LIBRARIES
rand_camera
CATKIN_DEPENDS
roslib
roscpp
gazebo_ros
geometry_msgs
std_srvs
std_msgs
gazebo_msgs
gazebo_ext_msgs
gazebo_plugins
)
include_directories(
include
${Boost_INCLUDE_DIRS}
${catkin_INCLUDE_DIRS}
src/skyx/include
${OGRE_INCLUDE_DIRS}/Paging
)
link_directories(${catkin_LIBRARY_DIRS})
# link_directories(${GAZEBO_LIBRARY_DIRS})
set(cxx_flags)
foreach (item ${GAZEBO_CFLAGS})
set(cxx_flags "${cxx_flags} ${item}")
endforeach ()
set(ld_flags)
foreach (item ${GAZEBO_LDFLAGS})
set(ld_flags "${ld_flags} ${item}")
endforeach ()
## Plugins
add_library(rand_camera src/RandCamera.cpp)
add_dependencies(rand_camera ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(rand_camera ${catkin_LIBRARIES} ${Boost_LIBRARIES} ${TinyXML_LIBRARIES} ${OpenCV_LIBS} ${GAZEBO_LIBRARIES})
# Install Gazebo System Plugins
install(TARGETS rand_camera
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
)
Asked by Whyamihere on 2018-10-23 09:40:32 UTC
Answers
By the look on your question i assume that you try to call the function like this:
VisualPtr vis = rendering::Scene::VisualAt(_camera, _Pos, _mod);
if thats the case the fix is easy. You need to call the functions on an scene pointer (not directly).
It would look like this.
rendering::ScenePtr scene_ = rendering::get_scene();
VisualPtr vis = scene_->VisualAt(_camera, _Pos, _mod);
Asked by wentz on 2018-11-02 08:47:21 UTC
Comments
Could you add the Gazebo version to your question? Also the CMakeLists file for your plugin should help.
Asked by chapulina on 2018-10-23 16:19:38 UTC
@chapulina, sure, updated
Asked by Whyamihere on 2018-10-23 19:01:55 UTC