diff --git a/cartographer_ros/CMakeLists.txt b/cartographer_ros/CMakeLists.txt index 83d7d2f..97f066e 100644 --- a/cartographer_ros/CMakeLists.txt +++ b/cartographer_ros/CMakeLists.txt @@ -28,26 +28,12 @@ set(PACKAGE_DEPENDENCIES tf2_ros ) -set(CMAKE_CXX_FLAGS "-pthread -std=c++11 -Wreorder") - -if(NOT CMAKE_BUILD_TYPE OR CMAKE_BUILD_TYPE STREQUAL "") - set(CMAKE_BUILD_TYPE Release) -endif() - -if(CMAKE_BUILD_TYPE STREQUAL "Release") - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -O3 -DNDEBUG") -elseif(CMAKE_BUILD_TYPE STREQUAL "RelWithDebInfo") - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -O3 -g -DNDEBUG") -elseif(CMAKE_BUILD_TYPE STREQUAL "Debug") - message(FATAL_ERROR "Cartographer is too slow to be useful in debug mode.") -else() - message(FATAL_ERROR "Unknown CMAKE_BUILD_TYPE: ${CMAKE_BUILD_TYPE}") -endif() - -message(STATUS "Build type: ${CMAKE_BUILD_TYPE}") +find_package(cartographer REQUIRED) +include("${CARTOGRAPHER_CMAKE_DIR}/functions.cmake") +google_initialize_cartographer_project() +google_enable_testing() find_package(catkin REQUIRED COMPONENTS ${PACKAGE_DEPENDENCIES}) -include_directories(${catkin_INCLUDE_DIRS}) catkin_package( CATKIN_DEPENDS @@ -56,84 +42,16 @@ catkin_package( ) find_package(PCL REQUIRED COMPONENTS common io) -include_directories(${PCL_INCLUDE_DIRS}) -link_directories(${PCL_LIBRARY_DIRS}) -add_definitions(${PCL_DEFINITIONS}) - find_package(Eigen3 REQUIRED) -include_directories(${EIGEN_INCLUDE_DIRS}) - -find_package(cartographer REQUIRED) -include_directories(${CARTOGRAPHER_INCLUDE_DIRS}) -link_directories(${CARTOGRAPHER_LIBRARY_DIRS}) - find_package(ZLIB REQUIRED) -include_directories(${ZLIB_INCLUDE_DIRS}) +find_package(Boost REQUIRED COMPONENTS system iostreams) -find_package(Boost REQUIRED - COMPONENTS - system - iostreams -) -add_definitions(${BOOST_DEFINITIONS}) -include_directories(${Boost_INCLUDE_DIRS}) -link_directories(${Boost_LIBRARY_DIRS}) - -add_executable(cartographer_node - src/cartographer_node_main.cc - src/map_writer.cc - src/map_writer.h - src/msg_conversion.cc - src/msg_conversion.h - src/node_options.cc - src/node_options.h - src/occupancy_grid.cc - src/occupancy_grid.h - src/ros_log_sink.cc - src/ros_log_sink.h - src/sensor_bridge.cc - src/sensor_bridge.h - src/sensor_data.h - src/tf_bridge.cc - src/tf_bridge.h - src/time_conversion.cc - src/time_conversion.h -) -target_link_libraries(cartographer_node - ${CARTOGRAPHER_LIBRARIES} - ${PCL_LIBRARIES} - ${catkin_LIBRARIES} - gflags - yaml-cpp -) -add_dependencies(cartographer_node - ${catkin_EXPORTED_TARGETS} -) - -catkin_add_gtest(time_conversion_test - src/time_conversion_test.cc - src/time_conversion.h - src/time_conversion.cc -) -target_link_libraries(time_conversion_test - ${CARTOGRAPHER_LIBRARIES} - ${GTEST_BOTH_LIBRARIES} - ${catkin_LIBRARIES} -) -add_dependencies(time_conversion_test - ${catkin_EXPORTED_TARGETS} -) +add_subdirectory("cartographer_ros") install(DIRECTORY launch urdf configuration_files DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} ) -install(TARGETS cartographer_node - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} -) - install(PROGRAMS scripts/tf_remove_frames.py DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} ) diff --git a/cartographer_ros/cartographer_ros/CMakeLists.txt b/cartographer_ros/cartographer_ros/CMakeLists.txt new file mode 100644 index 0000000..a77b82b --- /dev/null +++ b/cartographer_ros/cartographer_ros/CMakeLists.txt @@ -0,0 +1,131 @@ +google_library(map_writer + USES_GLOG + USES_ROS + USES_YAMLCPP + SRCS + map_writer.cc + HDRS + map_writer.h +) + +google_library(msg_conversion + USES_CARTOGRAPHER + USES_GLOG + USES_PCL + USES_ROS + SRCS + msg_conversion.cc + HDRS + msg_conversion.h + DEPENDS + time_conversion +) + +google_library(node_options + USES_CARTOGRAPHER + USES_GLOG + SRCS + node_options.cc + HDRS + node_options.h + DEPENDS + sensor_bridge +) + +google_library(occupancy_grid + USES_CARTOGRAPHER + USES_GLOG + USES_ROS + SRCS + occupancy_grid.cc + HDRS + occupancy_grid.h + DEPENDS + node_options + time_conversion +) + +google_library(ros_log_sink + USES_GLOG + USES_ROS + SRCS + ros_log_sink.cc + HDRS + ros_log_sink.h +) + +google_library(sensor_bridge + USES_CARTOGRAPHER + USES_ROS + SRCS + sensor_bridge.cc + HDRS + sensor_bridge.h + DEPENDS + msg_conversion + sensor_data + tf_bridge + time_conversion +) + +google_library(sensor_data + USES_CARTOGRAPHER + HDRS + sensor_data.h +) + +google_library(tf_bridge + USES_CARTOGRAPHER + SRCS + tf_bridge.cc + HDRS + tf_bridge.h + DEPENDS + msg_conversion + time_conversion +) + +google_library(time_conversion + USES_CARTOGRAPHER + USES_ROS + SRCS + time_conversion.cc + HDRS + time_conversion.h +) + +google_catkin_test(time_conversion_test + USES_CARTOGRAPHER + USES_ROS + SRCS + time_conversion_test.cc + DEPENDS + time_conversion +) + +google_binary(cartographer_node + USES_CARTOGRAPHER + USES_EIGEN + USES_GFLAGS + USES_GLOG + USES_ROS + SRCS + node_main.cc + DEPENDS + map_writer + msg_conversion + node_options + occupancy_grid + ros_log_sink + sensor_bridge + sensor_data + tf_bridge + time_conversion +) + +# TODO(hrapp): The update_cmakelists.py file will happy overwrite this. +install(TARGETS cartographer_node + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) diff --git a/cartographer_ros/src/map_writer.cc b/cartographer_ros/cartographer_ros/map_writer.cc similarity index 98% rename from cartographer_ros/src/map_writer.cc rename to cartographer_ros/cartographer_ros/map_writer.cc index aae7f02..4309a8a 100644 --- a/cartographer_ros/src/map_writer.cc +++ b/cartographer_ros/cartographer_ros/map_writer.cc @@ -14,7 +14,7 @@ * limitations under the License. */ -#include "map_writer.h" +#include "cartographer_ros/map_writer.h" #include diff --git a/cartographer_ros/src/map_writer.h b/cartographer_ros/cartographer_ros/map_writer.h similarity index 100% rename from cartographer_ros/src/map_writer.h rename to cartographer_ros/cartographer_ros/map_writer.h diff --git a/cartographer_ros/src/msg_conversion.cc b/cartographer_ros/cartographer_ros/msg_conversion.cc similarity index 99% rename from cartographer_ros/src/msg_conversion.cc rename to cartographer_ros/cartographer_ros/msg_conversion.cc index ed2edfd..2c3f216 100644 --- a/cartographer_ros/src/msg_conversion.cc +++ b/cartographer_ros/cartographer_ros/msg_conversion.cc @@ -14,13 +14,14 @@ * limitations under the License. */ -#include "msg_conversion.h" +#include "cartographer_ros/msg_conversion.h" #include "cartographer/common/port.h" #include "cartographer/common/time.h" #include "cartographer/sensor/proto/sensor.pb.h" #include "cartographer/transform/proto/transform.pb.h" #include "cartographer/transform/transform.h" +#include "cartographer_ros/time_conversion.h" #include "geometry_msgs/Pose.h" #include "geometry_msgs/Quaternion.h" #include "geometry_msgs/Transform.h" @@ -34,8 +35,6 @@ #include "sensor_msgs/MultiEchoLaserScan.h" #include "sensor_msgs/PointCloud2.h" -#include "time_conversion.h" - namespace cartographer_ros { namespace { diff --git a/cartographer_ros/src/msg_conversion.h b/cartographer_ros/cartographer_ros/msg_conversion.h similarity index 100% rename from cartographer_ros/src/msg_conversion.h rename to cartographer_ros/cartographer_ros/msg_conversion.h diff --git a/cartographer_ros/src/cartographer_node_main.cc b/cartographer_ros/cartographer_ros/node_main.cc similarity index 98% rename from cartographer_ros/src/cartographer_node_main.cc rename to cartographer_ros/cartographer_ros/node_main.cc index 3d98a2e..b51f57f 100644 --- a/cartographer_ros/src/cartographer_node_main.cc +++ b/cartographer_ros/cartographer_ros/node_main.cc @@ -46,6 +46,15 @@ #include "cartographer/sensor/proto/sensor.pb.h" #include "cartographer/transform/rigid_transform.h" #include "cartographer/transform/transform.h" +#include "cartographer_ros/map_writer.h" +#include "cartographer_ros/msg_conversion.h" +#include "cartographer_ros/node_options.h" +#include "cartographer_ros/occupancy_grid.h" +#include "cartographer_ros/ros_log_sink.h" +#include "cartographer_ros/sensor_bridge.h" +#include "cartographer_ros/sensor_data.h" +#include "cartographer_ros/tf_bridge.h" +#include "cartographer_ros/time_conversion.h" #include "cartographer_ros_msgs/FinishTrajectory.h" #include "cartographer_ros_msgs/SubmapEntry.h" #include "cartographer_ros_msgs/SubmapList.h" @@ -62,16 +71,6 @@ #include "tf2_ros/transform_broadcaster.h" #include "tf2_ros/transform_listener.h" -#include "map_writer.h" -#include "msg_conversion.h" -#include "node_options.h" -#include "occupancy_grid.h" -#include "ros_log_sink.h" -#include "sensor_bridge.h" -#include "sensor_data.h" -#include "tf_bridge.h" -#include "time_conversion.h" - DEFINE_string(configuration_directory, "", "First directory in which configuration files are searched, " "second is always the Cartographer installation to allow " diff --git a/cartographer_ros/src/node_options.cc b/cartographer_ros/cartographer_ros/node_options.cc similarity index 98% rename from cartographer_ros/src/node_options.cc rename to cartographer_ros/cartographer_ros/node_options.cc index 73dcec0..a3dc7be 100644 --- a/cartographer_ros/src/node_options.cc +++ b/cartographer_ros/cartographer_ros/node_options.cc @@ -14,7 +14,7 @@ * limitations under the License. */ -#include "node_options.h" +#include "cartographer_ros/node_options.h" #include "glog/logging.h" diff --git a/cartographer_ros/src/node_options.h b/cartographer_ros/cartographer_ros/node_options.h similarity index 97% rename from cartographer_ros/src/node_options.h rename to cartographer_ros/cartographer_ros/node_options.h index 78e87b7..bf7b0ee 100644 --- a/cartographer_ros/src/node_options.h +++ b/cartographer_ros/cartographer_ros/node_options.h @@ -23,7 +23,7 @@ #include "cartographer/common/port.h" #include "cartographer/mapping/map_builder.h" -#include "sensor_bridge.h" +#include "cartographer_ros/sensor_bridge.h" namespace cartographer_ros { diff --git a/cartographer_ros/src/occupancy_grid.cc b/cartographer_ros/cartographer_ros/occupancy_grid.cc similarity index 97% rename from cartographer_ros/src/occupancy_grid.cc rename to cartographer_ros/cartographer_ros/occupancy_grid.cc index 667a360..68041c9 100644 --- a/cartographer_ros/src/occupancy_grid.cc +++ b/cartographer_ros/cartographer_ros/occupancy_grid.cc @@ -14,10 +14,9 @@ * limitations under the License. */ -#include "occupancy_grid.h" - -#include "time_conversion.h" +#include "cartographer_ros/occupancy_grid.h" +#include "cartographer_ros/time_conversion.h" #include "glog/logging.h" namespace cartographer_ros { diff --git a/cartographer_ros/src/occupancy_grid.h b/cartographer_ros/cartographer_ros/occupancy_grid.h similarity index 96% rename from cartographer_ros/src/occupancy_grid.h rename to cartographer_ros/cartographer_ros/occupancy_grid.h index c44a773..8d9bba4 100644 --- a/cartographer_ros/src/occupancy_grid.h +++ b/cartographer_ros/cartographer_ros/occupancy_grid.h @@ -20,8 +20,8 @@ #include #include "cartographer/mapping/trajectory_node.h" +#include "cartographer_ros/node_options.h" #include "nav_msgs/OccupancyGrid.h" -#include "node_options.h" namespace cartographer_ros { diff --git a/cartographer_ros/src/ros_log_sink.cc b/cartographer_ros/cartographer_ros/ros_log_sink.cc similarity index 98% rename from cartographer_ros/src/ros_log_sink.cc rename to cartographer_ros/cartographer_ros/ros_log_sink.cc index 5e4c6c5..f5c7bbf 100644 --- a/cartographer_ros/src/ros_log_sink.cc +++ b/cartographer_ros/cartographer_ros/ros_log_sink.cc @@ -14,7 +14,7 @@ * limitations under the License. */ -#include "ros_log_sink.h" +#include "cartographer_ros/ros_log_sink.h" #include #include diff --git a/cartographer_ros/src/ros_log_sink.h b/cartographer_ros/cartographer_ros/ros_log_sink.h similarity index 100% rename from cartographer_ros/src/ros_log_sink.h rename to cartographer_ros/cartographer_ros/ros_log_sink.h diff --git a/cartographer_ros/src/sensor_bridge.cc b/cartographer_ros/cartographer_ros/sensor_bridge.cc similarity index 97% rename from cartographer_ros/src/sensor_bridge.cc rename to cartographer_ros/cartographer_ros/sensor_bridge.cc index 4ded8c6..94747d8 100644 --- a/cartographer_ros/src/sensor_bridge.cc +++ b/cartographer_ros/cartographer_ros/sensor_bridge.cc @@ -14,12 +14,11 @@ * limitations under the License. */ -#include "sensor_bridge.h" +#include "cartographer_ros/sensor_bridge.h" #include "cartographer/kalman_filter/pose_tracker.h" - -#include "msg_conversion.h" -#include "time_conversion.h" +#include "cartographer_ros/msg_conversion.h" +#include "cartographer_ros/time_conversion.h" namespace cartographer_ros { diff --git a/cartographer_ros/src/sensor_bridge.h b/cartographer_ros/cartographer_ros/sensor_bridge.h similarity index 97% rename from cartographer_ros/src/sensor_bridge.h rename to cartographer_ros/cartographer_ros/sensor_bridge.h index 4cfae39..d75d1b0 100644 --- a/cartographer_ros/src/sensor_bridge.h +++ b/cartographer_ros/cartographer_ros/sensor_bridge.h @@ -20,18 +20,17 @@ #include "cartographer/mapping/sensor_collator.h" #include "cartographer/transform/rigid_transform.h" #include "cartographer/transform/transform.h" +#include "cartographer_ros/sensor_data.h" +#include "cartographer_ros/tf_bridge.h" #include "geometry_msgs/Transform.h" #include "geometry_msgs/TransformStamped.h" #include "nav_msgs/OccupancyGrid.h" #include "nav_msgs/Odometry.h" -#include "sensor_data.h" #include "sensor_msgs/Imu.h" #include "sensor_msgs/LaserScan.h" #include "sensor_msgs/MultiEchoLaserScan.h" #include "sensor_msgs/PointCloud2.h" -#include "tf_bridge.h" - namespace cartographer_ros { struct SensorBridgeOptions { diff --git a/cartographer_ros/src/sensor_data.h b/cartographer_ros/cartographer_ros/sensor_data.h similarity index 100% rename from cartographer_ros/src/sensor_data.h rename to cartographer_ros/cartographer_ros/sensor_data.h diff --git a/cartographer_ros/src/tf_bridge.cc b/cartographer_ros/cartographer_ros/tf_bridge.cc similarity index 96% rename from cartographer_ros/src/tf_bridge.cc rename to cartographer_ros/cartographer_ros/tf_bridge.cc index f5bbcd6..d191f66 100644 --- a/cartographer_ros/src/tf_bridge.cc +++ b/cartographer_ros/cartographer_ros/tf_bridge.cc @@ -16,8 +16,8 @@ #include "cartographer/common/make_unique.h" -#include "msg_conversion.h" -#include "tf_bridge.h" +#include "cartographer_ros/msg_conversion.h" +#include "cartographer_ros/tf_bridge.h" namespace cartographer_ros { diff --git a/cartographer_ros/src/tf_bridge.h b/cartographer_ros/cartographer_ros/tf_bridge.h similarity index 97% rename from cartographer_ros/src/tf_bridge.h rename to cartographer_ros/cartographer_ros/tf_bridge.h index 1e05af6..55edac7 100644 --- a/cartographer_ros/src/tf_bridge.h +++ b/cartographer_ros/cartographer_ros/tf_bridge.h @@ -22,7 +22,7 @@ #include "cartographer/transform/rigid_transform.h" #include "tf2_ros/buffer.h" -#include "time_conversion.h" +#include "cartographer_ros/time_conversion.h" namespace cartographer_ros { diff --git a/cartographer_ros/src/time_conversion.cc b/cartographer_ros/cartographer_ros/time_conversion.cc similarity index 96% rename from cartographer_ros/src/time_conversion.cc rename to cartographer_ros/cartographer_ros/time_conversion.cc index 7dfda18..eb5e815 100644 --- a/cartographer_ros/src/time_conversion.cc +++ b/cartographer_ros/cartographer_ros/time_conversion.cc @@ -14,7 +14,7 @@ * limitations under the License. */ -#include "time_conversion.h" +#include "cartographer_ros/time_conversion.h" #include "cartographer/common/time.h" #include "ros/ros.h" diff --git a/cartographer_ros/src/time_conversion.h b/cartographer_ros/cartographer_ros/time_conversion.h similarity index 100% rename from cartographer_ros/src/time_conversion.h rename to cartographer_ros/cartographer_ros/time_conversion.h diff --git a/cartographer_ros/src/time_conversion_test.cc b/cartographer_ros/cartographer_ros/time_conversion_test.cc similarity index 96% rename from cartographer_ros/src/time_conversion_test.cc rename to cartographer_ros/cartographer_ros/time_conversion_test.cc index 693a67b..c7e110a 100644 --- a/cartographer_ros/src/time_conversion_test.cc +++ b/cartographer_ros/cartographer_ros/time_conversion_test.cc @@ -14,7 +14,7 @@ * limitations under the License. */ -#include "time_conversion.h" +#include "cartographer_ros/time_conversion.h" #include diff --git a/cartographer_ros_msgs/CMakeLists.txt b/cartographer_ros_msgs/CMakeLists.txt index 25723c8..18f1c56 100644 --- a/cartographer_ros_msgs/CMakeLists.txt +++ b/cartographer_ros_msgs/CMakeLists.txt @@ -16,23 +16,9 @@ cmake_minimum_required(VERSION 2.8.3) project(cartographer_ros_msgs) -set(CMAKE_CXX_FLAGS "-pthread -std=c++11 ${CMAKE_CXX_FLAGS}") - -if(NOT CMAKE_BUILD_TYPE OR CMAKE_BUILD_TYPE STREQUAL "") - set(CMAKE_BUILD_TYPE Release) -endif() - -if(CMAKE_BUILD_TYPE STREQUAL "Release") - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -O3 -DNDEBUG") -elseif(CMAKE_BUILD_TYPE STREQUAL "RelWithDebInfo") - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -O3 -g -DNDEBUG") -elseif(CMAKE_BUILD_TYPE STREQUAL "Debug") - message(FATAL_ERROR "Cartographer is too slow to be useful in debug mode.") -else() - message(FATAL_ERROR "Unknown CMAKE_BUILD_TYPE: ${CMAKE_BUILD_TYPE}") -endif() - -message(STATUS "Build type: ${CMAKE_BUILD_TYPE}") +find_package(Cartographer REQUIRED) +include("${CARTOGRAPHER_CMAKE_DIR}/functions.cmake") +google_initialize_cartographer_project() find_package(catkin REQUIRED COMPONENTS geometry_msgs message_generation) diff --git a/cartographer_ros_msgs/package.xml b/cartographer_ros_msgs/package.xml index 45dfeef..fae9f52 100644 --- a/cartographer_ros_msgs/package.xml +++ b/cartographer_ros_msgs/package.xml @@ -30,5 +30,7 @@ catkin + cartographer + message_generation diff --git a/cartographer_rviz/CMakeLists.txt b/cartographer_rviz/CMakeLists.txt index 9c5711d..bd6e2e1 100644 --- a/cartographer_rviz/CMakeLists.txt +++ b/cartographer_rviz/CMakeLists.txt @@ -23,26 +23,13 @@ set(PACKAGE_DEPENDENCIES rviz ) -set(CMAKE_CXX_FLAGS "-pthread -std=c++11 -Wreorder") - -if(NOT CMAKE_BUILD_TYPE OR CMAKE_BUILD_TYPE STREQUAL "") - set(CMAKE_BUILD_TYPE Release) -endif() - -if(CMAKE_BUILD_TYPE STREQUAL "Release") - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -O3 -DNDEBUG") -elseif(CMAKE_BUILD_TYPE STREQUAL "RelWithDebInfo") - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -O3 -g -DNDEBUG") -elseif(CMAKE_BUILD_TYPE STREQUAL "Debug") - message(FATAL_ERROR "Cartographer is too slow to be useful in debug mode.") -else() - message(FATAL_ERROR "Unknown CMAKE_BUILD_TYPE: ${CMAKE_BUILD_TYPE}") -endif() - -message(STATUS "Build type: ${CMAKE_BUILD_TYPE}") +find_package(Cartographer REQUIRED) +include("${CARTOGRAPHER_CMAKE_DIR}/functions.cmake") +google_initialize_cartographer_project() +find_package(Boost REQUIRED COMPONENTS system iostreams) find_package(catkin REQUIRED COMPONENTS ${PACKAGE_DEPENDENCIES}) -include_directories(${catkin_INCLUDE_DIRS}) +find_package(ZLIB REQUIRED) catkin_package( CATKIN_DEPENDS @@ -50,13 +37,6 @@ catkin_package( ${PACKAGE_DEPENDENCIES} ) -find_package(cartographer REQUIRED) -include_directories(${CARTOGRAPHER_INCLUDE_DIRS}) -link_directories(${CARTOGRAPHER_LIBRARY_DIRS}) - -find_package(ZLIB REQUIRED) -include_directories(${ZLIB_INCLUDE_DIRS}) - set(CMAKE_AUTOMOC ON) if(rviz_QT_VERSION VERSION_LESS "5") message(STATUS "Using Qt4 based on the rviz_QT_VERSION: ${rviz_QT_VERSION}") @@ -69,30 +49,23 @@ else() endif() add_definitions(-DQT_NO_KEYWORDS) -find_package(Boost REQUIRED - COMPONENTS - system - iostreams -) -add_definitions(${BOOST_DEFINITIONS}) -include_directories(${Boost_INCLUDE_DIRS}) -link_directories(${Boost_LIBRARY_DIRS}) +SET(ALL_LIBRARIES "" CACHE INTERNAL "ALL_LIBRARIES") -add_library(cartographer_rviz_submaps_visualization - src/drawable_submap.cc - src/drawable_submap.h - src/submaps_display.cc - src/submaps_display.h +add_subdirectory("cartographer_rviz") + +# Create an empty file for the shared library we require for RViz. +set(DUMMY_SOURCE ${CMAKE_CURRENT_BINARY_DIR}/empty.cc) +add_custom_command( + OUTPUT ${DUMMY_SOURCE} + COMMAND cmake -E touch ${DUMMY_SOURCE} + DEPENDS ${ARG_SRCS} ) +add_library(cartographer_rviz_submaps_visualization ${DUMMY_SOURCE}) target_link_libraries(cartographer_rviz_submaps_visualization - ${Boost_LIBRARIES} - ${CARTOGRAPHER_LIBRARIES} ${QT_LIBRARIES} - ${ZLIB_LIBRARIES} - ${catkin_LIBRARIES} -) -add_dependencies(cartographer_rviz_submaps_visualization - ${catkin_EXPORTED_TARGETS} + "-Wl,--whole-archive" + ${ALL_LIBRARIES} + "-Wl,--no-whole-archive" ) install(TARGETS cartographer_rviz_submaps_visualization diff --git a/cartographer_rviz/cartographer_rviz/CMakeLists.txt b/cartographer_rviz/cartographer_rviz/CMakeLists.txt new file mode 100644 index 0000000..e1a120c --- /dev/null +++ b/cartographer_rviz/cartographer_rviz/CMakeLists.txt @@ -0,0 +1,19 @@ +google_library(drawable_submap + USES_CARTOGRAPHER + USES_ROS + SRCS + drawable_submap.cc + HDRS + drawable_submap.h +) + +google_library(submaps_display + USES_CARTOGRAPHER + USES_ROS + SRCS + submaps_display.cc + HDRS + submaps_display.h + DEPENDS + drawable_submap +) diff --git a/cartographer_rviz/src/drawable_submap.cc b/cartographer_rviz/cartographer_rviz/drawable_submap.cc similarity index 96% rename from cartographer_rviz/src/drawable_submap.cc rename to cartographer_rviz/cartographer_rviz/drawable_submap.cc index e61abb9..b7dada4 100644 --- a/cartographer_rviz/src/drawable_submap.cc +++ b/cartographer_rviz/cartographer_rviz/drawable_submap.cc @@ -14,22 +14,22 @@ * limitations under the License. */ -#include "drawable_submap.h" - -#include -#include -#include -#include -#include -#include -#include -#include +#include "cartographer_rviz/drawable_submap.h" #include #include #include #include +#include "Eigen/Core" +#include "Eigen/Geometry" +#include "OgreGpuProgramParams.h" +#include "OgreImage.h" +#include "cartographer/common/port.h" +#include "cartographer_ros_msgs/SubmapQuery.h" +#include "eigen_conversions/eigen_msg.h" +#include "ros/ros.h" + namespace cartographer_rviz { namespace { diff --git a/cartographer_rviz/src/drawable_submap.h b/cartographer_rviz/cartographer_rviz/drawable_submap.h similarity index 87% rename from cartographer_rviz/src/drawable_submap.h rename to cartographer_rviz/cartographer_rviz/drawable_submap.h index 0d26504..a59394e 100644 --- a/cartographer_rviz/src/drawable_submap.h +++ b/cartographer_rviz/cartographer_rviz/drawable_submap.h @@ -17,24 +17,24 @@ #ifndef CARTOGRAPHER_RVIZ_SRC_DRAWABLE_SUBMAP_H_ #define CARTOGRAPHER_RVIZ_SRC_DRAWABLE_SUBMAP_H_ -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - #include +#include "Eigen/Core" +#include "Eigen/Geometry" +#include "OgreManualObject.h" +#include "OgreMaterial.h" +#include "OgreQuaternion.h" +#include "OgreSceneManager.h" +#include "OgreSceneNode.h" +#include "OgreTexture.h" +#include "OgreVector3.h" +#include "cartographer/common/mutex.h" +#include "cartographer_ros_msgs/SubmapEntry.h" +#include "cartographer_ros_msgs/SubmapQuery.h" +#include "ros/ros.h" +#include "rviz/display_context.h" +#include "rviz/frame_manager.h" + namespace cartographer_rviz { // Contains all the information needed to render a submap onto the final diff --git a/cartographer_rviz/src/submaps_display.cc b/cartographer_rviz/cartographer_rviz/submaps_display.cc similarity index 91% rename from cartographer_rviz/src/submaps_display.cc rename to cartographer_rviz/cartographer_rviz/submaps_display.cc index a35eb7b..c7495dd 100644 --- a/cartographer_rviz/src/submaps_display.cc +++ b/cartographer_rviz/cartographer_rviz/submaps_display.cc @@ -14,20 +14,20 @@ * limitations under the License. */ -#include "submaps_display.h" +#include "cartographer_rviz/submaps_display.h" -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include +#include "OgreResourceGroupManager.h" +#include "cartographer/common/make_unique.h" +#include "cartographer/common/mutex.h" +#include "cartographer_ros_msgs/SubmapList.h" +#include "cartographer_ros_msgs/SubmapQuery.h" +#include "geometry_msgs/TransformStamped.h" +#include "pluginlib/class_list_macros.h" +#include "ros/package.h" +#include "ros/ros.h" +#include "rviz/display_context.h" +#include "rviz/frame_manager.h" +#include "rviz/properties/string_property.h" namespace cartographer_rviz { diff --git a/cartographer_rviz/src/submaps_display.h b/cartographer_rviz/cartographer_rviz/submaps_display.h similarity index 88% rename from cartographer_rviz/src/submaps_display.h rename to cartographer_rviz/cartographer_rviz/submaps_display.h index e25bd98..98b4e35 100644 --- a/cartographer_rviz/src/submaps_display.h +++ b/cartographer_rviz/cartographer_rviz/submaps_display.h @@ -17,17 +17,16 @@ #ifndef CARTOGRAPHER_RVIZ_SRC_SUBMAPS_DISPLAY_H_ #define CARTOGRAPHER_RVIZ_SRC_SUBMAPS_DISPLAY_H_ -#include -#include -#include -#include -#include -#include - #include #include -#include "drawable_submap.h" +#include "cartographer/common/mutex.h" +#include "cartographer/common/port.h" +#include "cartographer_ros_msgs/SubmapList.h" +#include "cartographer_rviz/drawable_submap.h" +#include "rviz/message_filter_display.h" +#include "tf2_ros/buffer.h" +#include "tf2_ros/transform_listener.h" namespace cartographer_rviz {