diff --git a/.vscode/settings.json b/.vscode/settings.json new file mode 100644 index 0000000..9fe3140 --- /dev/null +++ b/.vscode/settings.json @@ -0,0 +1,5 @@ +{ + "files.associations": { + "*.jinja": "c" + } +} \ No newline at end of file diff --git a/copier.yml b/copier.yml index 3fb7139..4db319f 100644 --- a/copier.yml +++ b/copier.yml @@ -3,7 +3,7 @@ _answers_file: .copier/answers.service-ros2-ament_cmake.yml PACKAGE_NAME: default: myproject type: str - help: The folder your package lives in. Please avoid spaces. + help: The folder your package lives in. Please avoid spaces. It should start with a lower case letter and only contain lower case letters, digits, underscores, and dashes. PACKAGE_DESCRIPTION: default: The {{PACKAGE_NAME}} package @@ -22,7 +22,7 @@ LANGUAGES: - Python - CPP -RUN_COMMAND: ros2 run {{ PACKAGE_NAME }} {{ "my_node.py" if 'Python' in LANGUAGES else "my_node" if "CPP" in LANGUAGES else "yourcommandGoes here" }} +RUN_COMMAND: ros2 run {{ PACKAGE_NAME }} {{ "my_python_node.py" if 'Python' in LANGUAGES else "my_node" if "CPP" in LANGUAGES else "yourcommandGoes here" }} HEALTHCHECK: defualt: HEALTHCHECK --start-period=60s --start-interval=1s CMD /ros_entrypoint.sh ros2 topic list diff --git a/src/CMakeLists.txt.jinja b/src/CMakeLists.txt.jinja index 7f87d25..19c8509 100644 --- a/src/CMakeLists.txt.jinja +++ b/src/CMakeLists.txt.jinja @@ -8,12 +8,29 @@ endif() {% if "CPP" in LANGUAGES %} # find dependencies find_package(ament_cmake REQUIRED) +find_package(rclcpp REQUIRED) +find_package(std_msgs REQUIRED) # uncomment the following section in order to fill in # further dependencies manually. # find_package( REQUIRED) +{% endif %} +{% if "Python" in LANGUAGES %} +find_package(rclpy REQUIRED) +find_package(ament_cmake_python REQUIRED) +# Install Python modules +ament_python_install_package(scripts) +# Install Python executables +install(PROGRAMS + scripts/my_python_node.py + DESTINATION lib/${PROJECT_NAME} +) +{% endif %} + +{% if "CPP" in LANGUAGES %} include_directories(include) add_executable(my_node src/my_node.cpp) +ament_target_dependencies(my_node rclcpp std_msgs) target_include_directories(my_node PUBLIC $ $) @@ -36,4 +53,6 @@ if(BUILD_TESTING) ament_lint_auto_find_test_dependencies() endif() +{% if "CPP" in LANGUAGES %} ament_package() +{% endif %} diff --git a/src/package.xml.jinja b/src/package.xml.jinja index 92b004d..56a4031 100644 --- a/src/package.xml.jinja +++ b/src/package.xml.jinja @@ -7,17 +7,23 @@ {{MAINTAINER_NAME}} {{LICENSE}} + {% if "CPP" in LANGUAGES %} ament_cmake - + rclcpp + {% endif %} ament_lint_auto ament_lint_common - {% if "Python" in LANGUAGES %} rclpy - std_msgs {% endif %} + std_msgs + {% if "CPP" in LANGUAGES %} ament_cmake + {% endif %} + {% if ("Python" in LANGUAGES) and ("CPP" not in LANGUAGES) %} + ament_python + {% endif %} diff --git a/src/{%if 'CPP' in LANGUAGES%}src{%endif%}/my_node.cpp.jinja b/src/{%if 'CPP' in LANGUAGES%}src{%endif%}/my_node.cpp.jinja index a58086a..40463a0 100644 --- a/src/{%if 'CPP' in LANGUAGES%}src{%endif%}/my_node.cpp.jinja +++ b/src/{%if 'CPP' in LANGUAGES%}src{%endif%}/my_node.cpp.jinja @@ -1,10 +1,32 @@ -#include -#include "{{PACKAGE_NAME}}/my_node.hpp" -int main(int argc, char ** argv) -{ - (void) argc; - (void) argv; +#include - printf("hello world {{PACKAGE_NAME}} package\n"); +#include "rclcpp/rclcpp.hpp" +#include "std_msgs/msg/string.hpp" +#include "{{PACKAGE_NAME}}/my_node.hpp" //example include header file +using std::placeholders::_1; + +class MinimalSubscriber : public rclcpp::Node +{ + public: + MinimalSubscriber() + : Node("minimal_subscriber") + { + subscription_ = this->create_subscription( + "topic", 10, std::bind(&MinimalSubscriber::topic_callback, this, _1)); + } + + private: + void topic_callback(const std_msgs::msg::String::SharedPtr msg) const + { + RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg->data.c_str()); + } + rclcpp::Subscription::SharedPtr subscription_; +}; + +int main(int argc, char * argv[]) +{ + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); return 0; -} +} \ No newline at end of file diff --git a/src/{%if 'Python' in LANGUAGES%}scripts{%endif%}/my_node.py b/src/{%if 'Python' in LANGUAGES%}scripts{%endif%}/my_python_node.py similarity index 73% rename from src/{%if 'Python' in LANGUAGES%}scripts{%endif%}/my_node.py rename to src/{%if 'Python' in LANGUAGES%}scripts{%endif%}/my_python_node.py index fff0ae1..efce55b 100644 --- a/src/{%if 'Python' in LANGUAGES%}scripts{%endif%}/my_node.py +++ b/src/{%if 'Python' in LANGUAGES%}scripts{%endif%}/my_python_node.py @@ -1,13 +1,14 @@ +#!/usr/bin/env python3 import rclpy from rclpy.node import Node from std_msgs.msg import String -class MinimalPublisher(Node): +class MyNode(Node): def __init__(self): - super().__init__('minimal_publisher') + super().__init__('my_python_node') self.publisher_ = self.create_publisher(String, 'topic', 10) timer_period = 0.5 # seconds self.timer = self.create_timer(timer_period, self.timer_callback) @@ -17,21 +18,19 @@ class MinimalPublisher(Node): msg = String() msg.data = 'Hello World: %d' % self.i self.publisher_.publish(msg) - self.get_logger().info('Publishing: "%s"' % msg.data) + self.get_logger().info('Python Node Publishing: "%s"' % msg.data) self.i += 1 def main(args=None): rclpy.init(args=args) - - minimal_publisher = MinimalPublisher() - - rclpy.spin(minimal_publisher) + my_node = MyNode() + rclpy.spin(my_node) # Destroy the node explicitly # (optional - otherwise it will be done automatically # when the garbage collector destroys the node object) - minimal_publisher.destroy_node() + my_node.destroy_node() rclpy.shutdown() diff --git a/src/{%if 'Python' in LANGUAGES%}setup.cfg{%endif%} b/src/{%if 'Python' in LANGUAGES%}setup.cfg{%endif%} deleted file mode 100644 index 8d8c058..0000000 --- a/src/{%if 'Python' in LANGUAGES%}setup.cfg{%endif%} +++ /dev/null @@ -1,4 +0,0 @@ -[develop] -script_dir=$base/lib/my_node -[install] -install_scripts=$base/lib/my_node \ No newline at end of file diff --git a/src/{%if ('Python' in LANGUAGES) and ('CPP' not in LANGUAGES) %}resource{%endif%}/{{PACKAGE_NAME}} b/src/{%if ('Python' in LANGUAGES) and ('CPP' not in LANGUAGES) %}resource{%endif%}/{{PACKAGE_NAME}} new file mode 100644 index 0000000..e69de29 diff --git a/src/{%if ('Python' in LANGUAGES) and ('CPP' not in LANGUAGES)%}launch{%endif%}/{{PACKAGE_NAME}}.launch.py.jinja b/src/{%if ('Python' in LANGUAGES) and ('CPP' not in LANGUAGES)%}launch{%endif%}/{{PACKAGE_NAME}}.launch.py.jinja new file mode 100644 index 0000000..99107d7 --- /dev/null +++ b/src/{%if ('Python' in LANGUAGES) and ('CPP' not in LANGUAGES)%}launch{%endif%}/{{PACKAGE_NAME}}.launch.py.jinja @@ -0,0 +1,11 @@ +from launch import LaunchDescription +from launch_ros.actions import Node + +#Simple launch file to launch nodes. +def generate_launch_description(): + return LaunchDescription([ + Node( + package='{{PACKAGE_NAME}}', + executable='my_python_node', + ), + ]) \ No newline at end of file diff --git a/src/{%if ('Python' in LANGUAGES) and ('CPP' not in LANGUAGES)%}setup.cfg{%endif%}.jinja b/src/{%if ('Python' in LANGUAGES) and ('CPP' not in LANGUAGES)%}setup.cfg{%endif%}.jinja new file mode 100644 index 0000000..031534f --- /dev/null +++ b/src/{%if ('Python' in LANGUAGES) and ('CPP' not in LANGUAGES)%}setup.cfg{%endif%}.jinja @@ -0,0 +1,4 @@ +[develop] +script_dir=$base/lib/{{PACKAGE_NAME}} +[install] +install_scripts=$base/lib/{{PACKAGE_NAME}} \ No newline at end of file diff --git a/src/{%if 'Python' in LANGUAGES%}setup.py.jinja{%endif%} b/src/{%if ('Python' in LANGUAGES) and ('CPP' not in LANGUAGES)%}setup.py{%endif%}.jinja similarity index 72% rename from src/{%if 'Python' in LANGUAGES%}setup.py.jinja{%endif%} rename to src/{%if ('Python' in LANGUAGES) and ('CPP' not in LANGUAGES)%}setup.py{%endif%}.jinja index 439fc1f..7b61bf5 100644 --- a/src/{%if 'Python' in LANGUAGES%}setup.py.jinja{%endif%} +++ b/src/{%if ('Python' in LANGUAGES) and ('CPP' not in LANGUAGES)%}setup.py{%endif%}.jinja @@ -1,7 +1,7 @@ from setuptools import find_packages, setup import os from glob import glob -package_name = {{PACKAGE_NAME}} +package_name = '{{PACKAGE_NAME}}' setup( name=package_name, @@ -18,14 +18,14 @@ setup( ], install_requires=['setuptools'], zip_safe=True, - maintainer={{MAINTAINER_NAME}}, - maintainer_email={{MAINTAINER_EMAIL}}, - description={{PACKAGE_DESCRIPTION}}, - license={{LICENSE}}, + maintainer='{{MAINTAINER_NAME}}', + maintainer_email='{{MAINTAINER_EMAIL}}', + description="{{PACKAGE_DESCRIPTION | trim}}", + license='{{LICENSE}}', tests_require=['pytest'], entry_points={ 'console_scripts': [ - 'minimal_publisher = scripts.my_node:main' + 'my_python_node = scripts.my_python_node:main' ], }, )