Fix python and cpp standalone packages. or you can run both python and cpp nodes in one package!
This commit is contained in:
parent
b69cd7da3f
commit
c4ac2616e0
5
.vscode/settings.json
vendored
Normal file
5
.vscode/settings.json
vendored
Normal file
@ -0,0 +1,5 @@
|
||||
{
|
||||
"files.associations": {
|
||||
"*.jinja": "c"
|
||||
}
|
||||
}
|
@ -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
|
||||
|
@ -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(<dependency> 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
|
||||
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
|
||||
$<INSTALL_INTERFACE:include/${PROJECT_NAME}>)
|
||||
@ -36,4 +53,6 @@ if(BUILD_TESTING)
|
||||
ament_lint_auto_find_test_dependencies()
|
||||
endif()
|
||||
|
||||
{% if "CPP" in LANGUAGES %}
|
||||
ament_package()
|
||||
{% endif %}
|
||||
|
@ -7,17 +7,23 @@
|
||||
<maintainer email="{{MAINTAINER_EMAIL}}">{{MAINTAINER_NAME}}</maintainer>
|
||||
<license>{{LICENSE}}</license>
|
||||
|
||||
{% if "CPP" in LANGUAGES %}
|
||||
<buildtool_depend>ament_cmake</buildtool_depend>
|
||||
|
||||
<depend>rclcpp</depend>
|
||||
{% endif %}
|
||||
<test_depend>ament_lint_auto</test_depend>
|
||||
<test_depend>ament_lint_common</test_depend>
|
||||
|
||||
{% if "Python" in LANGUAGES %}
|
||||
<exec_depend>rclpy</exec_depend>
|
||||
<exec_depend>std_msgs</exec_depend>
|
||||
{% endif %}
|
||||
<exec_depend>std_msgs</exec_depend>
|
||||
|
||||
<export>
|
||||
{% if "CPP" in LANGUAGES %}
|
||||
<build_type>ament_cmake</build_type>
|
||||
{% endif %}
|
||||
{% if ("Python" in LANGUAGES) and ("CPP" not in LANGUAGES) %}
|
||||
<build_type>ament_python</build_type>
|
||||
{% endif %}
|
||||
</export>
|
||||
</package>
|
||||
|
@ -1,10 +1,32 @@
|
||||
#include <cstdio>
|
||||
#include "{{PACKAGE_NAME}}/my_node.hpp"
|
||||
int main(int argc, char ** argv)
|
||||
{
|
||||
(void) argc;
|
||||
(void) argv;
|
||||
#include <memory>
|
||||
|
||||
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<std_msgs::msg::String>(
|
||||
"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<std_msgs::msg::String>::SharedPtr subscription_;
|
||||
};
|
||||
|
||||
int main(int argc, char * argv[])
|
||||
{
|
||||
rclcpp::init(argc, argv);
|
||||
rclcpp::spin(std::make_shared<MinimalSubscriber>());
|
||||
rclcpp::shutdown();
|
||||
return 0;
|
||||
}
|
@ -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()
|
||||
|
||||
|
@ -1,4 +0,0 @@
|
||||
[develop]
|
||||
script_dir=$base/lib/my_node
|
||||
[install]
|
||||
install_scripts=$base/lib/my_node
|
@ -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',
|
||||
),
|
||||
])
|
@ -0,0 +1,4 @@
|
||||
[develop]
|
||||
script_dir=$base/lib/{{PACKAGE_NAME}}
|
||||
[install]
|
||||
install_scripts=$base/lib/{{PACKAGE_NAME}}
|
@ -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'
|
||||
],
|
||||
},
|
||||
)
|
Loading…
Reference in New Issue
Block a user