From ffb36f98c37237576674dc8bf628f61840957693 Mon Sep 17 00:00:00 2001 From: Jamie Snape Date: Wed, 28 Jun 2017 09:40:59 -0400 Subject: [PATCH] Remove automotive from CMake build --- drake/CMakeLists.txt | 3 - drake/automotive/CMakeLists.txt | 155 ------------------ drake/automotive/gen/CMakeLists.txt | 21 --- drake/automotive/maliput/CMakeLists.txt | 5 - drake/automotive/maliput/api/CMakeLists.txt | 12 -- .../maliput/api/test/CMakeLists.txt | 2 - .../automotive/maliput/dragway/CMakeLists.txt | 31 ---- .../maliput/dragway/test/CMakeLists.txt | 2 - .../maliput/monolane/CMakeLists.txt | 14 -- .../maliput/monolane/test/CMakeLists.txt | 15 -- drake/automotive/maliput/rndf/CMakeLists.txt | 40 ----- .../maliput/rndf/test/CMakeLists.txt | 39 ----- .../automotive/maliput/utility/CMakeLists.txt | 11 -- .../maliput/utility/test/CMakeLists.txt | 11 -- drake/automotive/test/CMakeLists.txt | 58 ------- 15 files changed, 419 deletions(-) delete mode 100644 drake/automotive/CMakeLists.txt delete mode 100644 drake/automotive/gen/CMakeLists.txt delete mode 100644 drake/automotive/maliput/CMakeLists.txt delete mode 100644 drake/automotive/maliput/api/CMakeLists.txt delete mode 100644 drake/automotive/maliput/api/test/CMakeLists.txt delete mode 100644 drake/automotive/maliput/dragway/CMakeLists.txt delete mode 100644 drake/automotive/maliput/dragway/test/CMakeLists.txt delete mode 100644 drake/automotive/maliput/monolane/CMakeLists.txt delete mode 100644 drake/automotive/maliput/monolane/test/CMakeLists.txt delete mode 100644 drake/automotive/maliput/rndf/CMakeLists.txt delete mode 100644 drake/automotive/maliput/rndf/test/CMakeLists.txt delete mode 100644 drake/automotive/maliput/utility/CMakeLists.txt delete mode 100644 drake/automotive/maliput/utility/test/CMakeLists.txt delete mode 100644 drake/automotive/test/CMakeLists.txt diff --git a/drake/CMakeLists.txt b/drake/CMakeLists.txt index c4baa9aa1f0c..73eccccc1883 100644 --- a/drake/CMakeLists.txt +++ b/drake/CMakeLists.txt @@ -170,9 +170,6 @@ add_subdirectory(util) add_subdirectory(solvers) add_subdirectory(systems) add_subdirectory(manipulation) -if(yaml-cpp_FOUND) - add_subdirectory(automotive) -endif() set(ENABLE_PYTHON_BINDINGS OFF) if(pybind11_FOUND AND NOT DISABLE_PYTHON AND NUMPY_FOUND) if (NUMPY_VERSION VERSION_LESS 1.7) diff --git a/drake/automotive/CMakeLists.txt b/drake/automotive/CMakeLists.txt deleted file mode 100644 index d649e91e1e3e..000000000000 --- a/drake/automotive/CMakeLists.txt +++ /dev/null @@ -1,155 +0,0 @@ -add_subdirectory(gen) -add_subdirectory(maliput) - -if(BUILD_TESTING) - add_subdirectory(test) -endif() - -add_library_with_exports(LIB_NAME drakeAutomotive SOURCE_FILES - bicycle_car.cc - calc_smooth_acceleration.cc - curve2.cc - gen/bicycle_car_parameters.cc - gen/bicycle_car_state.cc - gen/driving_command.cc - gen/euler_floating_joint_state.cc - gen/idm_planner_parameters.cc - gen/maliput_railcar_params.cc - gen/maliput_railcar_state.cc - gen/mobil_planner_parameters.cc - gen/pure_pursuit_params.cc - gen/simple_car_params.cc - gen/simple_car_state.cc - idm_controller.cc - idm_planner.cc - maliput/api/junction.cc - maliput/api/lane.cc - maliput/api/lane_data.cc - maliput/api/road_geometry.cc - maliput/api/segment.cc - maliput/monolane/arc_lane.cc - maliput/monolane/branch_point.cc - maliput/monolane/builder.cc - maliput/monolane/junction.cc - maliput/monolane/lane.cc - maliput/monolane/line_lane.cc - maliput/monolane/loader.cc - maliput/monolane/road_geometry.cc - maliput/monolane/segment.cc - maliput/utility/generate_obj.cc - maliput/utility/generate_urdf.cc - maliput_railcar.cc - mobil_planner.cc - monolane_onramp_merge.cc - pose_selector.cc - pure_pursuit.cc - pure_pursuit_controller.cc - road_path.cc - simple_car.cc - simple_powertrain.cc - trajectory_car.cc - ) -target_link_libraries(drakeAutomotive - drakeCommon - drakeSystemAnalysis - drakeSystemFramework - drakeSystemPrimitives - drakeRendering - fmt - Eigen3::Eigen - yaml-cpp - ) -drake_install_libraries(drakeAutomotive) -drake_install_headers( - bicycle_car.h - calc_smooth_acceleration.h - create_trajectory_params.h - curve2.h - idm_controller.h - idm_planner.h - maliput_railcar.h - mobil_planner.h - monolane_onramp_merge.h - road_path.h - pose_selector.h - pure_pursuit.h - pure_pursuit_controller.h - simple_car.h - simple_car_to_euler_floating_joint.h - simple_powertrain.h - trajectory_car.h - # N.B. The gen/*.h headers are installed by gen/CMakeLists.txt. - ) -drake_install_pkg_config_file(drake-automotive - TARGET drakeAutomotive - LIBS -ldrakeAutomotive - REQUIRES - drake-common - drake-rbsystem - drake-shapes - drake-system-analysis - drake-system-framework - drake-system-primitives - eigen3) - -if(lcm_FOUND) - include_directories(${PROJECT_SOURCE_DIR}/pod-build/lcmgen) - - add_library_with_exports(LIB_NAME drakeAutomotiveLcm SOURCE_FILES - automotive_simulator.cc - box_car_vis.cc - car_vis.cc - car_vis_applicator.cc - gen/bicycle_car_parameters_translator.cc - gen/bicycle_car_state_translator.cc - gen/driving_command_translator.cc - gen/euler_floating_joint_state_translator.cc - gen/maliput_railcar_params_translator.cc - gen/maliput_railcar_state_translator.cc - gen/simple_car_params_translator.cc - gen/simple_car_state_translator.cc - prius_vis.cc - ) - target_link_libraries(drakeAutomotiveLcm - drakeAutomotive - drakeLCMTypes - drakeMultibodyParsers - drakeRigidBodyPlant - ) - drake_install_libraries(drakeAutomotiveLcm) - drake_install_headers( - automotive_simulator.h - box_car_vis.h - car_vis.h - car_vis_applicator.h - prius_vis.h - # N.B. The gen/*.h headers are installed by gen/CMakeLists.txt. - ) - drake_install_pkg_config_file(drake-automotive-lcm - TARGET drakeAutomotiveLcm - LIBS -ldrakeAutomotiveLcm - REQUIRES - drake-automotive - drake-rigid-body-plant) - - add_executable(automotive_demo - automotive_demo.cc - create_trajectory_params.cc) - target_link_libraries(automotive_demo - drakeAutomotiveLcm - drakeMaliputDragway) - - add_executable(car_sim_lcm car_sim_lcm.cc car_sim_lcm_common.cc) - target_link_libraries(car_sim_lcm - drakeAutomotiveLcm - drakeLcmSystem - drakeRigidBodyPlant - drakeSystemAnalysis - drakeSystemControllers) - drake_add_test(NAME car_sim_lcm COMMAND car_sim_lcm --simulation_sec 0.01) - - # TODO(liang.fok) Enable the following unit test once the build system is able - # to automatically generate the speed_bump.obj file from the speed_bump.yaml - # file. - # drake_add_test(NAME car_sim_lcm COMMAND car_sim_lcm --with_speed_bump true --simulation_sec 0.01) -endif() diff --git a/drake/automotive/gen/CMakeLists.txt b/drake/automotive/gen/CMakeLists.txt deleted file mode 100644 index 81af68a96e38..000000000000 --- a/drake/automotive/gen/CMakeLists.txt +++ /dev/null @@ -1,21 +0,0 @@ -if(lcm_FOUND) - drake_install_headers( - bicycle_car_parameters.h - bicycle_car_parameters_translator.h - bicycle_car_state.h - bicycle_car_state_translator.h - driving_command.h - driving_command_translator.h - euler_floating_joint_state.h - euler_floating_joint_state_translator.h - idm_planner_parameters.h - maliput_railcar_params.h - maliput_railcar_params_translator.h - maliput_railcar_state.h - maliput_railcar_state_translator.h - simple_car_params.h - simple_car_params_translator.h - simple_car_state.h - simple_car_state_translator.h - ) -endif() diff --git a/drake/automotive/maliput/CMakeLists.txt b/drake/automotive/maliput/CMakeLists.txt deleted file mode 100644 index d59e86f175e7..000000000000 --- a/drake/automotive/maliput/CMakeLists.txt +++ /dev/null @@ -1,5 +0,0 @@ -add_subdirectory(api) -add_subdirectory(dragway) -add_subdirectory(monolane) -add_subdirectory(rndf) -add_subdirectory(utility) diff --git a/drake/automotive/maliput/api/CMakeLists.txt b/drake/automotive/maliput/api/CMakeLists.txt deleted file mode 100644 index 36737de6b37a..000000000000 --- a/drake/automotive/maliput/api/CMakeLists.txt +++ /dev/null @@ -1,12 +0,0 @@ -drake_install_headers( - branch_point.h - junction.h - lane.h - lane_data.h - road_geometry.h - segment.h - ) - -if(BUILD_TESTING) - add_subdirectory(test) -endif() diff --git a/drake/automotive/maliput/api/test/CMakeLists.txt b/drake/automotive/maliput/api/test/CMakeLists.txt deleted file mode 100644 index 894af0c894c0..000000000000 --- a/drake/automotive/maliput/api/test/CMakeLists.txt +++ /dev/null @@ -1,2 +0,0 @@ -drake_add_cc_test(maliput_test) -target_link_libraries(maliput_test drakeAutomotive) diff --git a/drake/automotive/maliput/dragway/CMakeLists.txt b/drake/automotive/maliput/dragway/CMakeLists.txt deleted file mode 100644 index 85a89943d858..000000000000 --- a/drake/automotive/maliput/dragway/CMakeLists.txt +++ /dev/null @@ -1,31 +0,0 @@ -add_library_with_exports(LIB_NAME drakeMaliputDragway SOURCE_FILES - branch_point.cc - junction.cc - lane.cc - road_geometry.cc - segment.cc) - -target_link_libraries(drakeMaliputDragway - drakeAutomotive - drakeCommon -) - -drake_install_libraries(drakeMaliputDragway) - -drake_install_headers( - branch_point.h - junction.h - lane.h - road_geometry.h - segment.h) - -add_executable(dragway_to_urdf dragway_to_urdf.cc) -target_link_libraries(dragway_to_urdf - drakeAutomotive - drakeCommon - drakeMaliputDragway - spruce) - -if(BUILD_TESTING) - add_subdirectory(test) -endif() diff --git a/drake/automotive/maliput/dragway/test/CMakeLists.txt b/drake/automotive/maliput/dragway/test/CMakeLists.txt deleted file mode 100644 index fc3e2659ab55..000000000000 --- a/drake/automotive/maliput/dragway/test/CMakeLists.txt +++ /dev/null @@ -1,2 +0,0 @@ -drake_add_cc_test(dragway_test) -target_link_libraries(dragway_test drakeMaliputDragway) diff --git a/drake/automotive/maliput/monolane/CMakeLists.txt b/drake/automotive/maliput/monolane/CMakeLists.txt deleted file mode 100644 index 8a38e39ce2f6..000000000000 --- a/drake/automotive/maliput/monolane/CMakeLists.txt +++ /dev/null @@ -1,14 +0,0 @@ -if(BUILD_TESTING) - add_subdirectory(test) -endif() - -drake_install_headers( - arc_lane.h - branch_point.h - builder.h - junction.h - lane.h - line_lane.h - road_geometry.h - segment.h - ) diff --git a/drake/automotive/maliput/monolane/test/CMakeLists.txt b/drake/automotive/maliput/monolane/test/CMakeLists.txt deleted file mode 100644 index 06ef7bfb2d8d..000000000000 --- a/drake/automotive/maliput/monolane/test/CMakeLists.txt +++ /dev/null @@ -1,15 +0,0 @@ -drake_add_cc_test(monolane_lanes_test) -target_link_libraries(monolane_lanes_test drakeAutomotive) - -drake_add_cc_test(monolane_builder_test) -target_link_libraries(monolane_builder_test drakeAutomotive) - -add_executable(yaml_load yaml_load.cc) -target_link_libraries(yaml_load drakeAutomotive yaml-cpp) -if(PYTHON_EXECUTABLE) - drake_add_test( - NAME yaml_load_test - COMMAND ${PYTHON_EXECUTABLE} - ${CMAKE_CURRENT_SOURCE_DIR}/yaml_load_test.py - $) -endif() diff --git a/drake/automotive/maliput/rndf/CMakeLists.txt b/drake/automotive/maliput/rndf/CMakeLists.txt deleted file mode 100644 index b9d1d69d4a2f..000000000000 --- a/drake/automotive/maliput/rndf/CMakeLists.txt +++ /dev/null @@ -1,40 +0,0 @@ -if(ignition-rndf0_FOUND) - - add_library_with_exports(LIB_NAME drakeMaliputRndf SOURCE_FILES - branch_point.cc - junction.cc - lane.cc - road_geometry.cc - segment.cc - spline_helpers.cc - spline_lane.cc - ) - - target_include_directories(drakeMaliputRndf PRIVATE - "${IGNITION-RNDF_INCLUDE_DIRS}" - ) - - target_link_libraries(drakeMaliputRndf - drakeCommon - drakeAutomotive - "${IGNITION-RNDF_LIBRARIES}" - ) - - drake_install_libraries(drakeMaliputRndf) - - drake_install_headers( - branch_point.h - junction.h - lane.h - road_geometry.h - segment.h - spline_helpers.h - spline_lane.h - ) - -endif() - - -if(BUILD_TESTING) - add_subdirectory(test) -endif() diff --git a/drake/automotive/maliput/rndf/test/CMakeLists.txt b/drake/automotive/maliput/rndf/test/CMakeLists.txt deleted file mode 100644 index f5db059c8185..000000000000 --- a/drake/automotive/maliput/rndf/test/CMakeLists.txt +++ /dev/null @@ -1,39 +0,0 @@ -if(ignition-rndf0_FOUND) - drake_add_cc_test(ignition_rndf_test) - target_include_directories(ignition_rndf_test PRIVATE - "${IGNITION-RNDF_INCLUDE_DIRS}" - ) - target_link_libraries(ignition_rndf_test "${IGNITION-RNDF_LIBRARIES}") - - drake_add_cc_test(junction_test) - target_include_directories(junction_test PRIVATE - "${IGNITION-RNDF_INCLUDE_DIRS}" - ) - target_link_libraries(junction_test - drakeMaliputRndf - "${IGNITION-RNDF_LIBRARIES}") - - drake_add_cc_test(spline_helpers_test) - target_include_directories(spline_helpers_test PRIVATE - "${IGNITION-RNDF_INCLUDE_DIRS}" - ) - target_link_libraries(spline_helpers_test - drakeMaliputRndf - "${IGNITION-RNDF_LIBRARIES}") - - drake_add_cc_test(road_geometry_test) - target_include_directories(road_geometry_test PRIVATE - "${IGNITION-RNDF_INCLUDE_DIRS}" - ) - target_link_libraries(road_geometry_test - drakeMaliputRndf - "${IGNITION-RNDF_LIBRARIES}") - - drake_add_cc_test(segment_test) - target_include_directories(segment_test PRIVATE - "${IGNITION-RNDF_INCLUDE_DIRS}" - ) - target_link_libraries(segment_test - drakeMaliputRndf - "${IGNITION-RNDF_LIBRARIES}") -endif() diff --git a/drake/automotive/maliput/utility/CMakeLists.txt b/drake/automotive/maliput/utility/CMakeLists.txt deleted file mode 100644 index 33fa2e59ccb9..000000000000 --- a/drake/automotive/maliput/utility/CMakeLists.txt +++ /dev/null @@ -1,11 +0,0 @@ -if(BUILD_TESTING) - add_subdirectory(test) -endif() - -drake_install_headers( - generate_obj.h - generate_urdf.h - ) - -add_executable(yaml_to_obj yaml_to_obj.cc) -target_link_libraries(yaml_to_obj drakeAutomotive yaml-cpp) diff --git a/drake/automotive/maliput/utility/test/CMakeLists.txt b/drake/automotive/maliput/utility/test/CMakeLists.txt deleted file mode 100644 index e71b26f06912..000000000000 --- a/drake/automotive/maliput/utility/test/CMakeLists.txt +++ /dev/null @@ -1,11 +0,0 @@ -drake_add_cc_test(generate_urdf_test) -target_link_libraries(generate_urdf_test drakeAutomotive spruce) - -if(PYTHON_EXECUTABLE) - drake_add_test( - NAME yaml_to_obj_test - COMMAND ${PYTHON_EXECUTABLE} - ${CMAKE_CURRENT_SOURCE_DIR}/yaml_to_obj_test.py - $ - SIZE medium) -endif() diff --git a/drake/automotive/test/CMakeLists.txt b/drake/automotive/test/CMakeLists.txt deleted file mode 100644 index 21df421fffe4..000000000000 --- a/drake/automotive/test/CMakeLists.txt +++ /dev/null @@ -1,58 +0,0 @@ -drake_add_cc_test(bicycle_car_test) -target_link_libraries(bicycle_car_test drakeAutomotive) - -drake_add_cc_test(calc_smooth_acceleration_test) -target_link_libraries(calc_smooth_acceleration_test drakeAutomotive) - -drake_add_cc_test(simple_powertrain_test) -target_link_libraries(simple_powertrain_test drakeAutomotive) - -drake_add_cc_test(curve2_test) -target_link_libraries(curve2_test drakeAutomotive) - -drake_add_cc_test(simple_car_test) -target_link_libraries(simple_car_test drakeAutomotive) - -drake_add_cc_test(simple_car_to_euler_floating_joint_test) -target_link_libraries(simple_car_to_euler_floating_joint_test drakeAutomotive) - -drake_add_cc_test(trajectory_car_test) -target_link_libraries(trajectory_car_test drakeAutomotive) - -drake_add_cc_test(idm_planner_test) -target_link_libraries(idm_planner_test drakeAutomotive) - -drake_add_cc_test(monolane_onramp_merge_test) -target_link_libraries(monolane_onramp_merge_test drakeAutomotive) - -drake_add_cc_test(pose_selector_test) -target_link_libraries(pose_selector_test - drakeAutomotive - drakeMaliputDragway) - -drake_add_cc_test(pure_pursuit_test) -target_link_libraries(pure_pursuit_test - drakeAutomotive - drakeMaliputDragway) - -drake_add_cc_test(pure_pursuit_controller_test) -target_link_libraries(pure_pursuit_controller_test - drakeAutomotive - drakeMaliputDragway) - -drake_add_cc_test(idm_controller_test) -target_link_libraries(idm_controller_test - drakeAutomotive - drakeMaliputDragway) - -drake_add_cc_test(road_path_test) -target_link_libraries(road_path_test - drakeAutomotive - drakeMaliputDragway) - -if(lcm_FOUND) - drake_add_cc_test(automotive_simulator_test) - target_link_libraries(automotive_simulator_test - drakeAutomotiveLcm - drakeMaliputDragway) -endif()