fix jinja template for CPP

This commit is contained in:
Burak Ozter 2024-10-15 14:18:43 -03:00
parent 6e18af05ed
commit 16d32be258

View File

@ -5,7 +5,6 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
{% if "CPP" in LANGUAGES %}
# find dependencies
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
@ -13,7 +12,6 @@ find_package(std_msgs REQUIRED)
# uncomment the following section in order to fill in
# further dependencies manually.
# find_package(<dependency> REQUIRED)
{% endif %}
{% if "Python" in LANGUAGES %}
find_package(rclpy REQUIRED)
@ -27,7 +25,6 @@ install(PROGRAMS
)
{% endif %}
{% if "CPP" in LANGUAGES %}
include_directories(include)
add_executable(my_node src/my_node.cpp)
ament_target_dependencies(my_node rclcpp std_msgs)
@ -39,8 +36,6 @@ target_compile_features(my_node PUBLIC c_std_99 cxx_std_17) # Require C99 and C
install(TARGETS my_node
DESTINATION lib/${PROJECT_NAME})
{% endif %}
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
@ -53,6 +48,5 @@ if(BUILD_TESTING)
ament_lint_auto_find_test_dependencies()
endif()
{% if "CPP" in LANGUAGES %}
ament_package()
{% endif %}