12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394 |
- cmake_minimum_required(VERSION 2.8.11)
- project(pilottoros)
- message(STATUS "Enter pilottoros")
- include(${CMAKE_SOURCE_DIR}/adcpilot.cmake)
- ## 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
- cv_bridge
- image_transport
- roscpp
- pluginlib
- sensor_msgs
- pcl_ros
- pcl_conversions
- autoware_msgs
- )
- find_package(Boost REQUIRED)
- find_package(OpenCV REQUIRED)
- find_package(Protobuf REQUIRED)
- set(CMAKE_INCLUDE_CURRENT_DIR ON)
- set(CMAKE_AUTOMOC ON)
- set(CMAKE_AUTOUIC ON)
- set(CMAKE_AUTORCC ON)
- if(CMAKE_COMPILER_IS_GNUCXX)
- set(CMAKE_CXX_FLAGS "-fPIC ${CMAKE_CXX_FLAGS}")
- message(STATUS "optional:-fPIC")
- endif(CMAKE_COMPILER_IS_GNUCXX)
- ## System dependencies are found with CMake's conventions
- # find_package(Boost REQUIRED COMPONENTS system)
- #find_package(Qt5Core REQUIRED)
- #qt5_wrap_cpp(MOC src/qt_ros_test.h)
- #qt5_wrap_ui(UIC src/qt_ros_test.ui)
- ## 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 client_plugin
- CATKIN_DEPENDS
- roscpp std_msgs
- sensor_msgs pluginlib
- pcl_ros pcl_conversions
- DEPENDS
- Boost
- OpenCV
- Protobuf
- # DEPENDS system_lib
- )
- ###########
- ## Build ##
- ###########
- ## Specify additional locations of header files
- ## Your package locations should be listed before other locations
- include_directories(
- ## INCLUDE_DIRS include
- ${CMAKE_CURRENT_BINARY_DIR}/..
- ${catkin_INCLUDE_DIRS} include
- ${Boost_INCLUDE_DIR}
- ${autoware_msgs_INCLUDE_DIRS}
- )
- ## Declare a C++ executable
- add_executable(${PROJECT_NAME}_node src/main.cpp src ./../../../../include/msgtype/rawpic.pb.cc ./../../../../include/msgtype/odom.pb.cc
- ./../../../../include/msgtype/mapdata.pb.cc )
- target_link_libraries(${PROJECT_NAME}_node ${catkin_LIBRARIES} ${OpenCV_LIBRARIES} ${Protobuf_LIBRARIES} Qt5Core Qt5Xml modulecomm)
|