CMakeLists.txt 2.6 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394
  1. cmake_minimum_required(VERSION 2.8.11)
  2. project(pilottoros)
  3. message(STATUS "Enter pilottoros")
  4. include(${CMAKE_SOURCE_DIR}/adcpilot.cmake)
  5. ## Find catkin macros and libraries
  6. ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
  7. ## is used, also find other catkin packages
  8. find_package(catkin REQUIRED COMPONENTS
  9. cv_bridge
  10. image_transport
  11. roscpp
  12. pluginlib
  13. sensor_msgs
  14. pcl_ros
  15. pcl_conversions
  16. autoware_msgs
  17. )
  18. find_package(Boost REQUIRED)
  19. find_package(OpenCV REQUIRED)
  20. find_package(Protobuf REQUIRED)
  21. set(CMAKE_INCLUDE_CURRENT_DIR ON)
  22. set(CMAKE_AUTOMOC ON)
  23. set(CMAKE_AUTOUIC ON)
  24. set(CMAKE_AUTORCC ON)
  25. if(CMAKE_COMPILER_IS_GNUCXX)
  26. set(CMAKE_CXX_FLAGS "-fPIC ${CMAKE_CXX_FLAGS}")
  27. message(STATUS "optional:-fPIC")
  28. endif(CMAKE_COMPILER_IS_GNUCXX)
  29. ## System dependencies are found with CMake's conventions
  30. # find_package(Boost REQUIRED COMPONENTS system)
  31. #find_package(Qt5Core REQUIRED)
  32. #qt5_wrap_cpp(MOC src/qt_ros_test.h)
  33. #qt5_wrap_ui(UIC src/qt_ros_test.ui)
  34. ## Uncomment this if the package has a setup.py. This macro ensures
  35. ## modules and global scripts declared therein get installed
  36. ## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
  37. # catkin_python_setup()
  38. ###################################
  39. ## catkin specific configuration ##
  40. ###################################
  41. ## The catkin_package macro generates cmake config files for your package
  42. ## Declare things to be passed to dependent projects
  43. ## INCLUDE_DIRS: uncomment this if you package contains header files
  44. ## LIBRARIES: libraries you create in this project that dependent projects also need
  45. ## CATKIN_DEPENDS: catkin_packages dependent projects also need
  46. ## DEPENDS: system dependencies of this project that dependent projects also need
  47. catkin_package(
  48. ## INCLUDE_DIRS include
  49. # LIBRARIES client_plugin
  50. CATKIN_DEPENDS
  51. roscpp std_msgs
  52. sensor_msgs pluginlib
  53. pcl_ros pcl_conversions
  54. DEPENDS
  55. Boost
  56. OpenCV
  57. Protobuf
  58. # DEPENDS system_lib
  59. )
  60. ###########
  61. ## Build ##
  62. ###########
  63. ## Specify additional locations of header files
  64. ## Your package locations should be listed before other locations
  65. include_directories(
  66. ## INCLUDE_DIRS include
  67. ${CMAKE_CURRENT_BINARY_DIR}/..
  68. ${catkin_INCLUDE_DIRS} include
  69. ${Boost_INCLUDE_DIR}
  70. ${autoware_msgs_INCLUDE_DIRS}
  71. )
  72. ## Declare a C++ executable
  73. add_executable(${PROJECT_NAME}_node src/main.cpp src ./../../../../include/msgtype/rawpic.pb.cc ./../../../../include/msgtype/odom.pb.cc
  74. ./../../../../include/msgtype/mapdata.pb.cc )
  75. target_link_libraries(${PROJECT_NAME}_node ${catkin_LIBRARIES} ${OpenCV_LIBRARIES} ${Protobuf_LIBRARIES} Qt5Core Qt5Xml modulecomm)