From 50d11eb5fd924f41cb2428dd970c5f2e84f57f1d Mon Sep 17 00:00:00 2001 From: Jennifer Buehler <jennifer.e.buehler@gmail.com> Date: Fri, 26 Feb 2016 16:18:17 +0100 Subject: [PATCH] moved world plugin loader into own package --- README.md | 4 +- gazebo_state_plugins/CMakeLists.txt | 10 +- gazebo_state_plugins/package.xml | 6 +- .../gazebo_fake_object_recognition.launch | 15 +++ gazebo_world_plugin_loader/CMakeLists.txt | 108 ++++++++++++++++++ .../config/WorldPluginsTemplate.config | 13 +++ .../GazeboPluginLoader.h | 2 +- .../launch/plugin_loader_template.launch | 5 + gazebo_world_plugin_loader/package.xml | 59 ++++++++++ .../src/GazeboPluginLoader.cpp | 6 +- 10 files changed, 211 insertions(+), 17 deletions(-) create mode 100644 gazebo_test_tools/launch/gazebo_fake_object_recognition.launch create mode 100644 gazebo_world_plugin_loader/CMakeLists.txt create mode 100644 gazebo_world_plugin_loader/config/WorldPluginsTemplate.config rename {gazebo_state_plugins/include/gazebo_state_plugins => gazebo_world_plugin_loader/include/gazebo_world_plugin_loader}/GazeboPluginLoader.h (96%) create mode 100644 gazebo_world_plugin_loader/launch/plugin_loader_template.launch create mode 100644 gazebo_world_plugin_loader/package.xml rename {gazebo_state_plugins => gazebo_world_plugin_loader}/src/GazeboPluginLoader.cpp (91%) diff --git a/README.md b/README.md index cf7f2c3..ccbb993 100644 --- a/README.md +++ b/README.md @@ -1,3 +1,5 @@ # gazebo-pkgs -A collection of tools and plugins for Gazebo +A collection of tools and plugins for Gazebo. + +Please also refer to [the wiki](https://github.com/JenniferBuehler/gazebo-pkgs/wiki) for more information. diff --git a/gazebo_state_plugins/CMakeLists.txt b/gazebo_state_plugins/CMakeLists.txt index 3d1d28e..6557029 100644 --- a/gazebo_state_plugins/CMakeLists.txt +++ b/gazebo_state_plugins/CMakeLists.txt @@ -7,6 +7,7 @@ project(gazebo_state_plugins) find_package( catkin REQUIRED COMPONENTS + gazebo_world_plugin_loader geometry_msgs roscpp shape_msgs @@ -61,9 +62,6 @@ add_library(gazebo_map_publisher src/GazeboMapPublisher.cpp ) -add_library(gazebo_plugin_loader - src/GazeboPluginLoader.cpp -) ## Declare a cpp executable add_executable(gazebo_request_object_info test/object_info_request.cpp) @@ -73,7 +71,6 @@ add_executable(gazebo_request_object_info test/object_info_request.cpp) add_dependencies(gazebo_request_object_info ${catkin_EXPORTED_TARGETS}) add_dependencies(gazebo_object_info ${catkin_EXPORTED_TARGETS}) add_dependencies(gazebo_map_publisher ${catkin_EXPORTED_TARGETS}) -add_dependencies(gazebo_plugin_loader ${catkin_EXPORTED_TARGETS}) ## Specify libraries to link a library or executable target against target_link_libraries(gazebo_object_info @@ -88,11 +85,6 @@ target_link_libraries(gazebo_request_object_info ${catkin_LIBRARIES} ) -target_link_libraries(gazebo_plugin_loader - ${GAZEBO_LIBRARIES} - ${catkin_LIBRARIES} -) - ############# ## Install ## diff --git a/gazebo_state_plugins/package.xml b/gazebo_state_plugins/package.xml index 2cf50d6..062325a 100644 --- a/gazebo_state_plugins/package.xml +++ b/gazebo_state_plugins/package.xml @@ -4,9 +4,7 @@ <version>0.0.0</version> <description> Offers topics and services related to the state of the world in - Gazebo. In particular offers a *system* plugin which can be - used to load other *world* plugins after the world has been - loaded, so it doesn't have to be specified in the Gazebo .world file. + Gazebo. </description> <!-- One maintainer tag required, multiple allowed, one person per tag --> @@ -46,10 +44,12 @@ <buildtool_depend>catkin</buildtool_depend> <build_depend>geometry_msgs</build_depend> <build_depend>roscpp</build_depend> + <build_depend>gazebo_world_plugin_loader</build_depend> <build_depend>shape_msgs</build_depend> <build_depend>std_msgs</build_depend> <build_depend>object_msgs</build_depend> <build_depend>eigen_conversions</build_depend> + <run_depend>gazebo_world_plugin_loader</run_depend> <run_depend>object_msgs</run_depend> <run_depend>eigen_conversions</run_depend> <run_depend>geometry_msgs</run_depend> diff --git a/gazebo_test_tools/launch/gazebo_fake_object_recognition.launch b/gazebo_test_tools/launch/gazebo_fake_object_recognition.launch new file mode 100644 index 0000000..8865f4c --- /dev/null +++ b/gazebo_test_tools/launch/gazebo_fake_object_recognition.launch @@ -0,0 +1,15 @@ +<launch> + ##################################### + # Load Gazebo world plugins + ##################################### + # Load parameters for Gazebo World Plugins to load + <include file="$(find gazebo_state_plugins)/launch/plugin_loader.launch"/> + + ##################################### + # Load Gazebo fake object detector + ##################################### + <include file="$(find gazebo_test_tools)/launch/fake_object_recognizer.launch"> + # use the default config file + <arg name="config_file" value="$(find gazebo_test_tools)/config/FakeObjectRecognizer.yaml"/> + </include> +</launch> diff --git a/gazebo_world_plugin_loader/CMakeLists.txt b/gazebo_world_plugin_loader/CMakeLists.txt new file mode 100644 index 0000000..94caa88 --- /dev/null +++ b/gazebo_world_plugin_loader/CMakeLists.txt @@ -0,0 +1,108 @@ +cmake_minimum_required(VERSION 2.8.3) +project(gazebo_world_plugin_loader) + +## Find catkin macros and libraries +## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) +## is used, also find other catkin packages +find_package( + catkin + REQUIRED COMPONENTS + roscpp + gazebo_ros +) + +find_package(gazebo REQUIRED) + +## Uncomment this if the package has a setup.py. This macro ensures +## modules and global scripts declared therein get installed +## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html +# catkin_python_setup() + +################################### +## catkin specific configuration ## +################################### +## The catkin_package macro generates cmake config files for your package +## Declare things to be passed to dependent projects +## INCLUDE_DIRS: uncomment this if you package contains header files +## LIBRARIES: libraries you create in this project that dependent projects also need +## CATKIN_DEPENDS: catkin_packages dependent projects also need +## DEPENDS: system dependencies of this project that dependent projects also need +catkin_package( +# INCLUDE_DIRS include + LIBRARIES gazebo_world_plugin_loader + CATKIN_DEPENDS roscpp gazebo_ros +# DEPENDS system_lib +) + +########### +## Build ## +########### + +## Specify additional locations of header files +## Your package locations should be listed before other locations +# include_directories(include) +include_directories( + include + ${catkin_INCLUDE_DIRS} + ${GAZEBO_INCLUDE_DIRS} +) + +add_library(gazebo_world_plugin_loader + src/GazeboPluginLoader.cpp +) + +add_dependencies(gazebo_world_plugin_loader ${catkin_EXPORTED_TARGETS}) + +target_link_libraries(gazebo_world_plugin_loader + ${GAZEBO_LIBRARIES} + ${catkin_LIBRARIES} +) + + +############# +## Install ## +############# + +# all install targets should use catkin DESTINATION variables +# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html + +## Mark executable scripts (Python etc.) for installation +## in contrast to setup.py, you can choose the destination +# install(PROGRAMS +# scripts/my_python_script +# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark executables and/or libraries for installation +# install(TARGETS gazebo_world_plugin_loader gazebo_world_plugin_loader_node +# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +# ) + +## Mark cpp header files for installation +# install(DIRECTORY include/${PROJECT_NAME}/ +# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} +# FILES_MATCHING PATTERN "*.h" +# PATTERN ".svn" EXCLUDE +# ) + +## Mark other files for installation (e.g. launch and bag files, etc.) +# install(FILES +# # myfile1 +# # myfile2 +# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +# ) + +############# +## Testing ## +############# + +## Add gtest based cpp test target and link libraries +# catkin_add_gtest(${PROJECT_NAME}-test test/test_gazebo_world_plugin_loader.cpp) +# if(TARGET ${PROJECT_NAME}-test) +# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) +# endif() + +## Add folders to be run by python nosetests +# catkin_add_nosetests(test) diff --git a/gazebo_world_plugin_loader/config/WorldPluginsTemplate.config b/gazebo_world_plugin_loader/config/WorldPluginsTemplate.config new file mode 100644 index 0000000..a8a7f50 --- /dev/null +++ b/gazebo_world_plugin_loader/config/WorldPluginsTemplate.config @@ -0,0 +1,13 @@ +# Template for world plugins configuration: +# Parameters read by GazeboPluginLoader. Contains +# names and library files of Gazebo World Plugins to be +# loaded. + +# name of world to load the plugins on. 'default' or +# empty string should yield the default world. +world_name: "default" + +# names and filenames of plugins to load +world_plugins: + #- name: <name-of-plugin> + # file: lib<libname>.so diff --git a/gazebo_state_plugins/include/gazebo_state_plugins/GazeboPluginLoader.h b/gazebo_world_plugin_loader/include/gazebo_world_plugin_loader/GazeboPluginLoader.h similarity index 96% rename from gazebo_state_plugins/include/gazebo_state_plugins/GazeboPluginLoader.h rename to gazebo_world_plugin_loader/include/gazebo_world_plugin_loader/GazeboPluginLoader.h index be3919f..aeff567 100644 --- a/gazebo_state_plugins/include/gazebo_state_plugins/GazeboPluginLoader.h +++ b/gazebo_world_plugin_loader/include/gazebo_world_plugin_loader/GazeboPluginLoader.h @@ -31,7 +31,7 @@ namespace gazebo * This plugin is a system plugin which has to be loaded * together with gazebo, e.g.: * - * ``gzserver -s libgazebo_plugin_loader.so`` + * ``gzserver -s libgazebo_world_plugin_loader.so`` * * **Limitation:** * diff --git a/gazebo_world_plugin_loader/launch/plugin_loader_template.launch b/gazebo_world_plugin_loader/launch/plugin_loader_template.launch new file mode 100644 index 0000000..57f1ae7 --- /dev/null +++ b/gazebo_world_plugin_loader/launch/plugin_loader_template.launch @@ -0,0 +1,5 @@ +<launch> + <!-- for each gazebo world plugin to be loaded, you may need to load individual ROS parameters. + You can do this from here. --> + <rosparam ns="<your-package>" file="$(find <your-package>)/config/<world-plugin-config>.yaml"/> +</launch> diff --git a/gazebo_world_plugin_loader/package.xml b/gazebo_world_plugin_loader/package.xml new file mode 100644 index 0000000..9cf746e --- /dev/null +++ b/gazebo_world_plugin_loader/package.xml @@ -0,0 +1,59 @@ +<?xml version="1.0"?> +<package> + <name>gazebo_world_plugin_loader</name> + <version>0.0.0</version> + <description> + Offers a *system* plugin which can be + used to load other *world* plugins after the world has been + loaded, so it doesn't have to be specified in the Gazebo "world" file. + </description> + + <!-- One maintainer tag required, multiple allowed, one person per tag --> + <!-- Example: --> + <maintainer email="jennifer.e.buehler@gmail.com">Jennifer Buehler</maintainer> + + + <!-- One license tag required, multiple allowed, one license per tag --> + <!-- Commonly used license strings: --> + <!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 --> + <license>GPLv3</license> + + + <!-- Url tags are optional, but mutiple are allowed, one per tag --> + <!-- Optional attribute type can be: website, bugtracker, or repository --> + <!-- Example: --> + <!-- <url type="website">http://wiki.ros.org/gazebo_world_plugin_loader</url> --> + + + <!-- Author tags are optional, mutiple are allowed, one per tag --> + <!-- Authors do not have to be maintianers, but could be --> + <!-- Example: --> + <!-- <author email="jane.doe@example.com">Jane Doe</author> --> + + + <!-- The *_depend tags are used to specify dependencies --> + <!-- Dependencies can be catkin packages or system dependencies --> + <!-- Examples: --> + <!-- Use build_depend for packages you need at compile time: --> + <!-- <build_depend>message_generation</build_depend> --> + <!-- Use buildtool_depend for build tool packages: --> + <!-- <buildtool_depend>catkin</buildtool_depend> --> + <!-- Use run_depend for packages you need at runtime: --> + <!-- <run_depend>message_runtime</run_depend> --> + <!-- Use test_depend for packages you need only for testing: --> + <!-- <test_depend>gtest</test_depend> --> + <buildtool_depend>catkin</buildtool_depend> + <build_depend>roscpp</build_depend> + <run_depend>roscpp</run_depend> + + <run_depend>gazebo_ros</run_depend> + <build_depend>gazebo_ros</build_depend> + + <!-- The export tag contains other, unspecified, tags --> + <export> + <!-- You can specify that this package is a metapackage here: --> + <!-- <metapackage/> --> + + <!-- Other tools can request additional information be placed here --> + </export> +</package> diff --git a/gazebo_state_plugins/src/GazeboPluginLoader.cpp b/gazebo_world_plugin_loader/src/GazeboPluginLoader.cpp similarity index 91% rename from gazebo_state_plugins/src/GazeboPluginLoader.cpp rename to gazebo_world_plugin_loader/src/GazeboPluginLoader.cpp index ef617ae..3017be7 100644 --- a/gazebo_state_plugins/src/GazeboPluginLoader.cpp +++ b/gazebo_world_plugin_loader/src/GazeboPluginLoader.cpp @@ -1,4 +1,4 @@ -#include <gazebo_state_plugins/GazeboPluginLoader.h> +#include <gazebo_world_plugin_loader/GazeboPluginLoader.h> #include <gazebo/physics/World.hh> #include <gazebo/physics/PhysicsIface.hh> @@ -41,7 +41,7 @@ void GazeboPluginLoader::onWorldCreate(){ node.getParam("world_plugins", world_plugins); if (world_plugins.getType() != XmlRpc::XmlRpcValue::TypeArray) { - ROS_ERROR("Parameter world_plugins should be specified as an array"); + ROS_ERROR("Parameter world_plugins should be specified as an array. Gazebo world plugins won't be loaded."); return; } @@ -50,7 +50,7 @@ void GazeboPluginLoader::onWorldCreate(){ { if (!world_plugins[i].hasMember("name") || !world_plugins[i].hasMember("file")) { - ROS_ERROR("World plugin parameter specification should have 'name' and 'file'"); + ROS_ERROR("World plugin parameter specification should have 'name' and 'file'. Gazebo world plugins won't be loaded."); continue; } std::string name=world_plugins[i]["name"]; -- GitLab