|
1 | 1 | cmake_minimum_required(VERSION 2.8.3) |
2 | 2 | project(advanced_navigation_driver) |
3 | 3 |
|
4 | | -## Compile as C++11, supported in ROS Kinetic and newer |
5 | 4 | add_compile_options(-std=c++11) |
6 | 5 |
|
7 | | -## Find catkin macros and libraries |
8 | | -## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) |
9 | | -## is used, also find other catkin packages |
10 | 6 | find_package(catkin REQUIRED COMPONENTS |
| 7 | + diagnostic_msgs |
| 8 | + nav_msgs |
11 | 9 | roscpp |
| 10 | + sensor_msgs |
12 | 11 | std_msgs |
| 12 | + tf |
13 | 13 | ) |
14 | 14 |
|
15 | | -## System dependencies are found with CMake's conventions |
16 | | -# find_package(Boost REQUIRED COMPONENTS system) |
| 15 | +catkin_package() |
17 | 16 |
|
18 | | - |
19 | | -## Uncomment this if the package has a setup.py. This macro ensures |
20 | | -## modules and global scripts declared therein get installed |
21 | | -## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html |
22 | | -# catkin_python_setup() |
23 | | - |
24 | | -################################################ |
25 | | -## Declare ROS messages, services and actions ## |
26 | | -################################################ |
27 | | - |
28 | | -## To declare and build messages, services or actions from within this |
29 | | -## package, follow these steps: |
30 | | -## * Let MSG_DEP_SET be the set of packages whose message types you use in |
31 | | -## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...). |
32 | | -## * In the file package.xml: |
33 | | -## * add a build_depend tag for "message_generation" |
34 | | -## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET |
35 | | -## * If MSG_DEP_SET isn't empty the following dependency has been pulled in |
36 | | -## but can be declared for certainty nonetheless: |
37 | | -## * add a run_depend tag for "message_runtime" |
38 | | -## * In this file (CMakeLists.txt): |
39 | | -## * add "message_generation" and every package in MSG_DEP_SET to |
40 | | -## find_package(catkin REQUIRED COMPONENTS ...) |
41 | | -## * add "message_runtime" and every package in MSG_DEP_SET to |
42 | | -## catkin_package(CATKIN_DEPENDS ...) |
43 | | -## * uncomment the add_*_files sections below as needed |
44 | | -## and list every .msg/.srv/.action file to be processed |
45 | | -## * uncomment the generate_messages entry below |
46 | | -## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...) |
47 | | - |
48 | | -## Generate messages in the 'msg' folder |
49 | | -# add_message_files( |
50 | | -# FILES |
51 | | -# Message1.msg |
52 | | -# Message2.msg |
53 | | -# ) |
54 | | - |
55 | | -## Generate services in the 'srv' folder |
56 | | -# add_service_files( |
57 | | -# FILES |
58 | | -# Service1.srv |
59 | | -# Service2.srv |
60 | | -# ) |
61 | | - |
62 | | -## Generate actions in the 'action' folder |
63 | | -# add_action_files( |
64 | | -# FILES |
65 | | -# Action1.action |
66 | | -# Action2.action |
67 | | -# ) |
68 | | - |
69 | | -## Generate added messages and services with any dependencies listed here |
70 | | -# generate_messages( |
71 | | -# DEPENDENCIES |
72 | | -# std_msgs |
73 | | -# ) |
74 | | - |
75 | | -################################################ |
76 | | -## Declare ROS dynamic reconfigure parameters ## |
77 | | -################################################ |
78 | | - |
79 | | -## To declare and build dynamic reconfigure parameters within this |
80 | | -## package, follow these steps: |
81 | | -## * In the file package.xml: |
82 | | -## * add a build_depend and a run_depend tag for "dynamic_reconfigure" |
83 | | -## * In this file (CMakeLists.txt): |
84 | | -## * add "dynamic_reconfigure" to |
85 | | -## find_package(catkin REQUIRED COMPONENTS ...) |
86 | | -## * uncomment the "generate_dynamic_reconfigure_options" section below |
87 | | -## and list every .cfg file to be processed |
88 | | - |
89 | | -## Generate dynamic reconfigure parameters in the 'cfg' folder |
90 | | -# generate_dynamic_reconfigure_options( |
91 | | -# cfg/DynReconf1.cfg |
92 | | -# cfg/DynReconf2.cfg |
93 | | -# ) |
94 | | - |
95 | | -################################### |
96 | | -## catkin specific configuration ## |
97 | | -################################### |
98 | | -## The catkin_package macro generates cmake config files for your package |
99 | | -## Declare things to be passed to dependent projects |
100 | | -## INCLUDE_DIRS: uncomment this if you package contains header files |
101 | | -## LIBRARIES: libraries you create in this project that dependent projects also need |
102 | | -## CATKIN_DEPENDS: catkin_packages dependent projects also need |
103 | | -## DEPENDS: system dependencies of this project that dependent projects also need |
104 | | -catkin_package( |
105 | | -# INCLUDE_DIRS include |
106 | | -# LIBRARIES an_driver |
107 | | -# CATKIN_DEPENDS roscpp std_msgs |
108 | | -# DEPENDS system_lib |
109 | | -) |
110 | | - |
111 | | -########### |
112 | | -## Build ## |
113 | | -########### |
114 | | - |
115 | | -## Specify additional locations of header files |
116 | | -## Your package locations should be listed before other locations |
117 | | -include_directories( |
118 | | -# include |
| 17 | +include_directories( |
119 | 18 | ${catkin_INCLUDE_DIRS} |
120 | 19 | ) |
121 | 20 |
|
122 | | -## Declare a C++ library |
123 | | -# add_library(${PROJECT_NAME} |
124 | | -# src/${PROJECT_NAME}/an_driver.cpp |
125 | | -# ) |
126 | | - |
127 | | -## Add cmake target dependencies of the library |
128 | | -## as an example, code may need to be generated before libraries |
129 | | -## either from message generation or dynamic reconfigure |
130 | | -# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) |
131 | | - |
132 | | -## Declare a C++ executable |
133 | | -## With catkin_make all packages are built within a single CMake context |
134 | | -## The recommended prefix ensures that target names across packages don't collide |
135 | | -# add_executable(${PROJECT_NAME}_node src/an_driver_node.cpp) |
136 | | - |
137 | | -## Rename C++ executable without prefix |
138 | | -## The above recommended prefix causes long target names, the following renames the |
139 | | -## target back to the shorter version for ease of user use |
140 | | -## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node" |
141 | | -# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "") |
142 | | - |
143 | | -## Add cmake target dependencies of the executable |
144 | | -## same as for the library above |
145 | | -# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) |
146 | | - |
147 | | -## Specify libraries to link a library or executable target against |
148 | | -# target_link_libraries(${PROJECT_NAME}_node |
149 | | -# ${catkin_LIBRARIES} |
150 | | -# ) |
151 | | - |
152 | | -############# |
153 | | -## Install ## |
154 | | -############# |
155 | | - |
156 | | -# all install targets should use catkin DESTINATION variables |
157 | | -# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html |
158 | | - |
159 | | -## Mark executable scripts (Python etc.) for installation |
160 | | -## in contrast to setup.py, you can choose the destination |
161 | | -# install(PROGRAMS |
162 | | -# scripts/my_python_script |
163 | | -# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} |
164 | | -# ) |
165 | | - |
166 | | -## Mark executables and/or libraries for installation |
167 | | -# install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node |
168 | | -# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} |
169 | | -# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} |
170 | | -# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} |
171 | | -# ) |
172 | | - |
173 | | -## Mark cpp header files for installation |
174 | | -# install(DIRECTORY include/${PROJECT_NAME}/ |
175 | | -# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} |
176 | | -# FILES_MATCHING PATTERN "*.h" |
177 | | -# PATTERN ".svn" EXCLUDE |
178 | | -# ) |
179 | | - |
180 | | -## Mark other files for installation (e.g. launch and bag files, etc.) |
181 | | -# install(FILES |
182 | | -# # myfile1 |
183 | | -# # myfile2 |
184 | | -# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} |
185 | | -# ) |
186 | | - |
187 | | -############# |
188 | | -## Testing ## |
189 | | -############# |
190 | | - |
191 | | -## Add gtest based cpp test target and link libraries |
192 | | -# catkin_add_gtest(${PROJECT_NAME}-test test/test_an_driver.cpp) |
193 | | -# if(TARGET ${PROJECT_NAME}-test) |
194 | | -# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME}) |
195 | | -# endif() |
196 | | - |
197 | | -## Add folders to be run by python nosetests |
198 | | -# catkin_add_nosetests(test) |
199 | | - |
200 | | -######################### |
201 | | -## Advanced Navigation ## |
202 | | -######################### |
203 | 21 | add_executable(advanced_navigation_driver src/an_driver.cpp src/spatial_packets.c src/an_packet_protocol.c src/rs232/rs232.c) |
204 | 22 | target_link_libraries(advanced_navigation_driver ${catkin_LIBRARIES}) |
0 commit comments