4. ROS Packages¶
We already covered the basics of ROS in our wiki.
In this part, we will explain the basic structure of our ROS packages.
They all share a basic structure that will be explained through the
simulation.src.simulation_onboarding
package. This package is located at
simulation/src/simulation_onboarding
and will be used throughout the onboarding.
simulation/src/simulation_onboarding
├── launch
│ ├── master.launch
│ └── onboarding_node.launch
├── msg
│ └── Speed.msg
├── param
│ └── onboarding
│ ├── default.yaml
│ └── topics.yaml
├── scripts
│ └── onboarding_node
├── src
│ ├── onboarding
│ │ ├── __init__.py
│ │ └── node.py
│ └── __init__.py
├── CMakeLists.txt
├── __init__.py
├── package.xml
└── setup.py
4.1. Launch directory¶
Inside the launch
directory are files which define what should be done when you execute
for example this command:
roslaunch simulation_onboarding master.launch road:=<ROAD_NAME>
Let’s break this command down:
simulation_onboarding is the name of the ROS Package.
master.launch is the name of the launch file that is launched by roslaunch.
road:=<ROAD_NAME> is used to pass the launch file the argument road with a value of <ROAD_NAME.
Let’s take a look at master.launch
:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 | <?xml version="1.0" encoding="UTF-8"?>
<!-- Launch script for starting onboarding node and full simulation -->
<launch>
<!-- Define a launch argument with the <arg>. The argument is called `road` and must be set when using roslaunch: `roslaunch simulation_onboarding master.launch road:=${NAME_OF_ROAD}`-->
<arg name="road" />
<!-- include_brain is false by default.-->
<arg name="include_brain" default="false" />
<arg name="include_vehicle_simulation" default="false" />
<!-- Use <include> to include other launch files. In this case the simulation master.launch file is included; it starts a Gazebo-world and by default also the KITcar_brain. KITcar_brain is the software which controls our vehicle! -->
<include file="$(find gazebo_simulation)/launch/master.launch">
<!-- Tell the master.launch which road to launch. -->
<arg name="road" value="$(arg road)" />
<!-- The include_brain argument is passed to tell the master.launch file if KITcar_brain should be launch as well. -->
<arg name="include_brain" value="$(arg include_brain)" />
<arg name="include_vehicle_simulation" value="$(arg include_vehicle_simulation)" />
</include>
<!-- Launch onboarding node -->
<include file="$(find simulation_onboarding)/launch/onboarding_node.launch" />
</launch>
|
As you can see, two arguments are defined and used within the launch file
master.launch
. The onboarding_node.launch
file is included and also launched. Let’s take a look at it:
1 2 3 4 5 6 7 8 9 10 11 | <?xml version="1.0" encoding="UTF-8"?>
<!-- Launch script for onboarding node -->
<launch>
<!-- Start a node with the <node> tag. The `pkg` and `type` attribute specify which script should be called to start the node. Here, the script is located at simulation_onboarding/scripts/simulation_onboarding -->
<node name="onboarding_node" ns="simulation_onboarding" pkg="simulation_onboarding" type="onboarding_node" output="screen">
<!-- Load parameters from default.yaml with <rosparam>.-->
<rosparam file="$(find simulation_onboarding)/param/onboarding/default.yaml" command="load"/>
<!-- Load parameters from topics.yaml with <rosparam>. In this case, the parameters are loaded into the namespace `topics`. Namespaces allow to load a number of parameter files without conflicts. The parameters can then be accessed within the node. -->
<rosparam file="$(find simulation_onboarding)/param/onboarding/topics.yaml" command="load" ns="topics" />
</node>
</launch>
|
The onboarding_node gets executed with additional parameters loaded from topics.yaml
.
4.2. Message directory¶
ROS messages are defined inside the directory msg
. Each *.msg file defines a new
message type. Learn more about ROS messages at http://wiki.ros.org/Messages. You can see an
example here:
1 2 3 | # Definition of the Speed message
# - Beginning sphinx -
float32 speed
|
4.3. Parameter directory¶
Each node has its own sub-directory inside the param
directory.
In there is always a file called topics.yaml
.
It defines the topics which are published from the node.
Here is the topics.yaml
:
1 | topic_name: /simulation/onboarding/topic
|
Additionally, the directory usually contains the default.yaml
file; it defines parameters
used within the node:
1 2 | param_name_1: param_value_1
param_name_2: param_value_2
|
Note
Using parameters in nodes creates programs with flexible behavior and code that does not depend on magic-numbers, i.e. numbers that are defined within the code and are very hard to read!
4.4. Scripts directory¶
The scripts
directory contains python scripts that can start ROS nodes.
The scripts/onboarding_node
is called when launching onboarding_node.launch which in
turn initializes an instance of OnboardingNode:
1 2 3 4 5 6 7 8 9 10 | #! /usr/bin/env python3
from contextlib import suppress
import rospy
from onboarding.node import OnboardingNode
if __name__ == "__main__":
# Start the node
with suppress(rospy.ROSInterruptException):
OnboardingNode()
|
Now you know how roslaunch uses python scripts to start nodes.
4.5. Source directory¶
The src
directory is the heart of every ROS package. It contains the actual Python code
defining ROS nodes. Each node is defined within a sub-directory (== python package) within
src
. Inside this sub-directory, you can find the node and sometimes additional Python
modules that add functionality to it. In this example, the onboarding node is defined in the
module node.py
within the src/onboarding
directory.
We will explain this code in the next chapter, but for integrity, here is the
file node.py
:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 | """OnboardingNode."""
from simulation.utils.ros_base.node_base import NodeBase
class OnboardingNode(NodeBase):
"""ROS node to teach new members."""
def __init__(self):
"""Initialize the node."""
super().__init__(name="onboarding_node")
# Start running node
# This will do the following
# 1) Call self.start()
# 2) Call self.steer() 60 times a second!
# 3) Call self.stop() when ROS is shutting down
self.run(function=self.steer, rate=60)
def start(self):
"""Start node."""
# When overwriting a function, ensure that the original function (NodeBase.start())
# is also called
super().start()
def stop(self):
"""Turn off node."""
# When overwriting a function, ensure that the original function (NodeBase.stop())
# is also called
super().stop()
def steer(self):
"""Control the car's pose to drive along the road."""
pass
|
4.6. CMakeLists file¶
The file CMakeLists.txt
contains information for the compiler so it knows what has to be
done when it gets executed.
It should be executed in $KITCAR_REPO_PATH/kitcar-gazebo-simulation/simulation/
with
the command:
catkin_make
The file looks like this:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 | cmake_minimum_required(VERSION 2.8.3)
project(simulation_onboarding)
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
message_generation
std_msgs
)
## System dependencies are found with CMake's conventions
## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installed
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
catkin_python_setup()
################################################
## Declare ROS messages, services and actions ##
################################################
# Add message definitions
add_message_files(
FILES
Speed.msg # Add this line for every message
)
generate_messages(
DEPENDENCIES
std_msgs
###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## INCLUDE_DIRS: uncomment this if your package contains header files
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
# INCLUDE_DIRS include
# CATKIN_DEPENDS gazebo_ros_pkgs
CATKIN_DEPENDS message_runtime std_msgs
# DEPENDS roscpp gazebo_ros
)
#############
## Testing ##
#############
## Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test test/test_gazebo_simulation.cpp)
# if(TARGET ${PROJECT_NAME}-test)
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
# endif()
## Add folders to be run by python nosetests
# catkin_add_nosetests(test)
if(CATKIN_ENABLE_TESTING)
find_package(rostest REQUIRED)
endif()
|
4.7. Package file¶
The file package.xml
holds metadata about this ROS Package:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 | <?xml version="1.0"?>
<package format="2">
<name>simulation_onboarding</name>
<version>0.0.0</version>
<description>The simulation_onboarding package</description>
<maintainer email="kitcar-simulation@lists.kit.edu">KITcar Simulation</maintainer>
<license>MIT</license>
<buildtool_depend>catkin</buildtool_depend>
<build_depend>genmsgs</build_depend>
<build_depend>message_generation</build_depend>
<build_depend>rospy</build_depend>
<build_depend>roscpp</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>rostest</build_depend>
<build_export_depend>std_msgs</build_export_depend>
<exec_depend>message_runtime</exec_depend>
</package>
|
4.8. Setup file¶
The setup.py
file tells cmake where the Python packages are located:
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 | from distutils.core import setup
from catkin_pkg.python_setup import generate_distutils_setup
# fetch values from package.xml
# fmt: off
setup_args = generate_distutils_setup(
# Packages contains all foldernames inside the package_dir
packages=(
[
'onboarding', # Include package with onboarding node
]
),
package_dir={"": "src"},
)
# fmt: on
setup(**setup_args)
|