Using custom ROS2 messages in gazebo plugin
Hi,
i have a ros2 project setup where one of the packages contains all my custom messages and services. I'm currently building a gazebo11 plugin and i want to use those custom messages. I've put the plugin in a ROS2 package and I am building it with colcon. I've manages to put together a CMakeLists.txt file that compiles but I had to explicitly include the path to the ros2 install file.
cmake_minimum_required(VERSION 3.5)
project(gazebo_plugin)
set(CMAKE_CXX_STANDARD 17)
find_package(ament_cmake REQUIRED)
find_package(std_msgs REQUIRED)
find_package(gazebo_dev REQUIRED)
find_package(gazebo_msgs REQUIRED)
find_package(gazebo_ros REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(interfaces REQUIRED)
include_directories(${gazebo_ros_INCLUDE_DIRS})
include_directories(${rclcpp_INCLUDE_DIRS})
include_directories(${std_msgs_INCLUDE_DIRS})
include_directories(${GAZEBO_INCLUDE_DIRS})
include_directories(/ws/um_ws/ros2/install/interfaces/include)
link_directories(${GAZEBO_LIBRARY_DIRS})
add_library(motion_controller SHARED src/motion_controller.cc )
target_link_libraries(motion_controller ${GAZEBO_LIBRARIES} ${rclcpp_LIBRARIES} ${std_msgs_LIBRARIES} ${gazebo_ros_LIBRARIES} ${geometry_msgs_LIBRARIES})
ament_package()
However, when I run gazebo with a world that includes my plugin with cusom messages i get an error message like this:
gzserver: symbol lookup error: /ws/um_ws/ros2/build/gazebo_plugin/libmotion_controller.so: undefined symbol: _ZN22rosidl_typesupport_cpp31get_message_type_s
upport_handleIN10interfaces3msg15MotorXYControl_ISaIvEEEEEPK29rosidl_message_type_support_tv
How would i go about fixing this?