In this post it will be shown how to organize your ROS2 package in such manner that allows you to have as many python scripts as you need. It is a quite simple way of doing it, but can be confusing for those who are coming from ROS 1. Let’s check it out!
Configuring environment
In order to do that in a way anyone can reproduce, let’s use the App of TheconstructSim. Start by creating a new rosject here
After creating it, just hit the Run button and wait for the desktop environment to get ready.
Create the ROS package
With the environment ready, create a new ROS 2 package inside the given workspace. Use the commands below:
cd ~/ros2_ws/src ros2 pkg create --build-type ament_python pkg1 --dependencies rclpycies rclpy
You must have the package created like in the image below:
Create the script files
Create the first script files you want to have in your package:
cd ~/ros2_ws/src touch pkg1/pkg1/hello_world.py chmod +x pkg1/pkg1/hello_world.py touch pkg1/pkg1/goodbye_world.py chmod +x pkg1/pkg1/goodbye_world.py
You must be able to edit the files from the IDE at this point:
Go to the root workspace:
- Compile the package
- Source the workspace
- Check that your package is added to ROS environment
cd ~/ros2_ws colcon build source install/setup.bash ros2 pkg list | grep pkg1
Add some code to the scripts to have some nodes
Add the code below to the hello_world.py script:
import rclpy from rclpy.node import Node class MyNode(Node): def __init__(self): # call super() in the constructor in order to initialize the Node object # the parameter we pass is the node name super().__init__('hello_world') # create a timer sending two parameters: # - the duration between 2 callbacks (0.2 seeconds) # - the timer function (timer_callback) self.create_timer(0.2, self.timer_callback) def timer_callback(self): # print a ROS2 log on the terminal with a great message! self.get_logger().info("Hello World!") def main(args=None): # initialize the ROS communication rclpy.init(args=args) # declare the node constructor node = MyNode() # pause the program execution, waits for a request to kill the node (ctrl+c) rclpy.spin(node) # shutdown the ROS communication rclpy.shutdown() if __name__ == '__main__': main()
And the same for the goodbye_world.py, just changing the info text
import rclpy from rclpy.node import Node class MyNode(Node): def __init__(self): # call super() in the constructor in order to initialize the Node object # the parameter we pass is the node name super().__init__('hello_world') # create a timer sending two parameters: # - the duration between 2 callbacks (0.2 seeconds) # - the timer function (timer_callback) self.create_timer(0.2, self.timer_callback) def timer_callback(self): # print a ROS2 log on the terminal with a great message! self.get_logger().info("Goodbye World!") def main(args=None): # initialize the ROS communication rclpy.init(args=args) # declare the node constructor node = MyNode() # pause the program execution, waits for a request to kill the node (ctrl+c) rclpy.spin(node) # shutdown the ROS communication rclpy.shutdown() if __name__ == '__main__': main()
Create a launch file
In order to run both scripts at the same time, let’s create a launch file:
cd ~/ros2_ws/src touch pkg1/launch/hello_goodbye.launch chmod +x pkg1/launch/hello_goodbye.launch
Add the following content:
from launch import LaunchDescription from launch_ros.actions import Node def generate_launch_description(): return LaunchDescription([ Node( package='pkg1', executable='hello_world', output='screen'), Node( package='pkg1', executable='goodbye_world', output='screen'), ])
Configure the setup.py of the package
In order to add the launch file to the setup, it must contain some libraries like os and glob. The content of the file ~/ros2_ws/src/pkg1/setup.py will look like below:
from setuptools import setup import os from glob import glob package_name = 'pkg1' setup( name=package_name, version='0.0.0', packages=[package_name], data_files=[ ('share/ament_index/resource_index/packages', ['resource/' + package_name]), ('share/' + package_name, ['package.xml']), (os.path.join('share', package_name), glob('launch/*.launch.py')) ], install_requires=['setuptools'], zip_safe=True, maintainer='user', maintainer_email='user@todo.todo', description='TODO: Package description', license='TODO: License declaration', tests_require=['pytest'], entry_points={ 'console_scripts': [ 'hello_world = pkg1.hello_world:main', 'goodbye_world = pkg1.goodbye_world:main' ], }, )
Compile and run
Compile the package once more and run the launch file
cd ~/ros2_ws colcon build source install/setup.bash ros2 launch pkg1 hello_goodbye.launch.py
The expected result is in the image below:
0 Comments