Skip to content

Commit

Permalink
Refactored Warehouse ROS for pluginlib
Browse files Browse the repository at this point in the history
  • Loading branch information
TheBrewCrew authored and 130s committed Jun 16, 2016
1 parent df1ba8d commit 66c6b11
Show file tree
Hide file tree
Showing 31 changed files with 841 additions and 1,930 deletions.
60 changes: 18 additions & 42 deletions CMakeLists.txt
@@ -1,61 +1,37 @@
cmake_minimum_required(VERSION 2.8.3)
project(warehouse_ros)

set(CMAKE_MODULE_PATH "${PROJECT_SOURCE_DIR}/cmake/" ${CMAKE_MODULE_PATH})

find_package(catkin REQUIRED COMPONENTS
geometry_msgs
find_package(catkin REQUIRED
roscpp
rostime
std_msgs)
if (CATKIN_ENABLE_TESTING)
find_package(rostest REQUIRED)
endif()
find_package(Boost REQUIRED COMPONENTS system)
find_package(OpenSSL)
find_package(MongoDB)

set(MONGO_EXPORT)
if("${MongoDB_LIBRARIES}" MATCHES "\\.so$")
set(MONGO_EXPORT MongoDB)
endif()

file(MAKE_DIRECTORY "${CATKIN_DEVEL_PREFIX}/include")

catkin_python_setup()
std_msgs
geometry_msgs
pluginlib
tf
)
find_package(Boost COMPONENTS system filesystem thread)

catkin_package(
INCLUDE_DIRS ${CATKIN_DEVEL_PREFIX}/include include test
INCLUDE_DIRS include
LIBRARIES warehouse_ros
CATKIN_DEPENDS roscpp geometry_msgs rostime std_msgs
DEPENDS Boost ${MONGO_EXPORT}
)

include(cmake/FindMongoDB.cmake)
CATKIN_DEPENDS roscpp rostime std_msgs geometry_msgs
DEPENDS Boost
)

if (NOT MongoDB_EXPOSE_MACROS)
add_definitions(-DMONGO_EXPOSE_MACROS)
endif()
configure_file("include/mongo_ros/config.h.in" "${CATKIN_DEVEL_PREFIX}/include/mongo_ros/config.h")

include_directories(${CATKIN_DEVEL_PREFIX}/include include test ${catkin_INCLUDE_DIRS} ${MongoDB_INCLUDE_DIR} ${Boost_INCLUDE_DIRS})
include_directories(include ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS})
link_directories(${catkin_LINK_DIRS})
link_directories(${Boost_LIBRARY_DIRS})

set(warehouse_srcs
src/mongo_ros.cpp
src/mongo_ros_dummy.cpp)
src/database_loader.cpp
src/transform_collection.cpp)

add_library(warehouse_ros SHARED ${warehouse_srcs})
target_link_libraries(warehouse_ros ${catkin_LIBRARIES} ${MongoDB_LIBRARIES} ${OPENSSL_LIBRARIES} ${Boost_LIBRARIES})

if (CATKIN_ENABLE_TESTING)
add_executable(test_mongo_roscpp test/test_mongo_ros.cpp)
target_link_libraries(test_mongo_roscpp ${catkin_LIBRARIES} ${MongoDB_LIBRARIES} ${OPENSSL_LIBRARIES} ${Boost_LIBRARIES})
add_rostest(test/mongo_ros.test)
endif()
target_link_libraries(warehouse_ros ${catkin_LIBRARIES} ${Boost_LIBRARIES})

add_executable(warehouse_test_dbloader src/test_dbloader.cpp)
target_link_libraries(warehouse_test_dbloader warehouse_ros ${catkin_LIBRARIES} ${Boost_LIBRARIES})

install(TARGETS warehouse_ros LIBRARY DESTINATION lib)
install(DIRECTORY include/ DESTINATION include FILES_MATCHING PATTERN "*.h" PATTERN "*.hpp")
install(PROGRAMS src/mongo_wrapper_ros.py DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})
install(FILES "${CATKIN_DEVEL_PREFIX}/include/mongo_ros/config.h" DESTINATION include/mongo_ros)
4 changes: 1 addition & 3 deletions README.md
@@ -1,3 +1 @@
Code for persisting ROS message data using MongoDB. Contains C++ and Python libraries to serialize ROS data to MongoDB, as well as some handy scripts to record data from the command line. See http://www.ros.org/wiki/warehousewg for more.

master branch: [![Build Status](https://travis-ci.org/ros-planning/warehouse_ros.png?branch=master)](https://travis-ci.org/ros-planning/warehouse_ros)
Abstract interface for persisting ROS message data. Implementations are loaded using pluginlib. Currently has one implementation, using MongoDB, warehouse_ros_mongo. See http://www.ros.org/wiki/warehousewg for more.
67 changes: 0 additions & 67 deletions cmake/FindMongoDB.cmake

This file was deleted.

0 comments on commit 66c6b11

Please sign in to comment.