Publishers and Subscriber Activity
Tasks
Basic Node
Create a node that accomplishes the following:
- Publishes to
cmd_vel
at10 Hz
and causes the turtle to move forward in the \(x\) direction - Subscribes to
pose
and, when the turtle's \(x\) coordinate is less than 2 or greater than 7 reverses the turtle direction
Step-by-Step Guide
Here is an approximate step-by-step guide.
- Create a new ROS workspace
- Create a new
ament_python
package- After calling
ros2 pkg create ...
is a good time to init thegit
repository and make the first commit - After editing
package.xml
,setup.py
and creating theREADME.md
is a good time for the second commit.
- After calling
- Create a minimal ROS node:
- At first, all that is needed is an entry point that logs a message:
- Create the python file to hold the node, the node class, and the entry point function
- Add the entry point to the
setup.py
- Build the workspace, run, make sure it works, and commit to
git
- At first, all that is needed is an entry point that logs a message:
- Next, create a timer. At first the timer just logs information so that you know the timer is running.
- After the timer runs successfully, commit to
git
- After the timer runs successfully, commit to
- Run the turtlesim node.
- You can use
ros2
commands to find out information about the turtlesim - The
turtlesim
also has documentation on http://index.ros.org - The ROS 1 documentation on the wiki (linked to on http://index.ros.org) still provides accurate descriptions of the
turtlesim
ROS API.
- You can use
- Create a publisher that publishes on the
cmd_vel
topic (use a relative topic name)- Publish the command required to accomplish the task
- Update the
package.xml
with the package that contains the message type used - Use
ros2 topic
to verify that the command is publishing the correct information at the correct frequency. - Commit to
git
- Using
ros2 run
start theturtlesim
and your node.- Make sure to
remap
thecmd_vel
argument toturtle1/cmd_vel
when you run your node - See Naming in ROS for more information
- Adjust code as needed until this step works, and commit to
git
(at least once when the task is complete).
- Make sure to
- Write an XML launchfile called
two_pubsub.launch.xml
to start theturtlesim
node and your node. Once it works, commit it to git.- Don't forget to add turtlesim as an
exec_depend
, since your launchfile depends on it. - There are multiple ways to write this launchfile. For this task use the
remap
tag toremap
the topics in your node to theturtlesim
topics.
- Don't forget to add turtlesim as an
- Now add the subscriber to the node:
- Update the launchfile to ensure this topic is mapped properly (subscribe to a relative topic name)
- At first do nothing in the subscriber other than log a message
- Run your node and the
turtlesim
and make sure the subscriber can be called - Once the subscriber is called, commit to
git
- Now, make the
subscriber
control the direction of the turtle- The
subscriber
callback and thetimer
callback can share information via class member variables initialized in__init__
.
- The
- Once you can run the node and have the turtle move back and forth, this task is complete.
- A git commit is appropriate here.
Custom Parameters
- Control the minimum and maximum \(x\) values using parameters called
xmin
andxmax
. - Make sure the parameters have meaningful default values and have the node log the parameter values to the DEBUG log when it starts.
- Test that the node is reading the parameters correctly using
ros2 run
with debugging enabled for the node and commit to git. - Add the arguments to the launch file that let the user set
xmin
andxmax
during launch.- When the launchfile works, commit to git
- See Parameters and ROS Python API for more information.
Namespaces
- Run two instances of your node and the
turtlesim
in two separate namespaces with two separatexmin
andxmax
values.- If you implemented your node correctly, you should not need to change any code to accomplish this task.
- This exercise should be done using only
ros2 run
- Try to accomplish this without remapping the
cmd_vel
orpose
topics but instead running your node in the correct namespace - See Name Remapping for more information.
- Write a launchfile called
two_pubsub.launch.xml
that starts your node and the turtlesim node- Use a
group
,push_ros_namespace
,include
to include the launchfile made in the previous section but get the included nodes to launch in a different namespaces.
- Use a
Service Call
- When your node starts (and before it begins moving the turtle) spawn two new turtles, one at the
xmin
and one at thexmax
values- The ROS 2 Service Client Tutorial may help
- You can use
rclpy.spin_until_future_complete
here as the service is not being called from a callback. - See Service Client for more details
Answers
This section contains the answers. Try to avoid looking at the answers unless you are truly stuck or want to verify your work after completing the task.
Basic Node
Creating The Workspace
mkdir -p ws/activity/src cd ws/activity/src ros2 pkg create --build-type ament_python pubsub cd pubsub git init git add package.xml pubsub/__init__.py resource/pubsub git add setup.cfg setup.py test/test_copyright.py test/test_flake8.py test/test_pep257.py git commit
Editing package.xml and setup.py
<?xml version="1.0"?> <?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?> <package format="3"> <name>pubsub</name> <version>0.1.0</version> <description>A pubsub Demo</description> <maintainer email="youremail@domain.edu">Your Name</maintainer> <license>GPLv3</license> <exec_depend>rclpy</exec_depend> <test_depend>ament_copyright</test_depend> <test_depend>ament_flake8</test_depend> <test_depend>ament_pep257</test_depend> <test_depend>python3-pytest</test_depend> <export> <build_type>ament_python</build_type> </export> </package>
from setuptools import find_packages, setup package_name = 'pubsub' setup( name=package_name, version='0.0.0', packages=find_packages(exclude=['test']), data_files=[ ('share/ament_index/resource_index/packages', ['resource/' + package_name]), ('share/' + package_name, ['package.xml']), ], install_requires=['setuptools'], zip_safe=True, maintainer='Your Name', maintainer_email='youremail@domain.edu', description='A pubsub demo', license='GPLv3', tests_require=['pytest'], entry_points={ 'console_scripts': [ ], }, )
# Pub Sub Activity Author: Your Name This is an activity to practice with publishers and subscribers and launchfiles
Minimal Node
entry_points={ 'console_scripts': [ 'pubsub_node = pubsub.pubsub:main' ],
import rclpy from rclpy.node import Node class PubsubNode(Node): def __init__(self): super().__init__("pubsub") self.get_logger().info("Pubsub Node") def main(args=None): rclpy.init(args=args) pubsub_node = PubsubNode() rclpy.spin(pubsub_node) pubsub_node.destroy_node() rclpy.shutdown()
Creating the Timer
# Just showing the pubsub node class PubsubNode(Node): def __init__(self): super().__init__("pubsub") self.get_logger().info("Pubsub Node") self._tmr = self.create_timer(0.1, self.timer_callback) def timer_callback(self): self.get_logger().info("Timer!")
Running the turtlesim node
ros2 run turtlesim turtlesim node # In a new window, list all the topics ros2 topic list # Get info on /turtle1/cmd_vel ros2 topic info /turtle1/cmd_vel # See that the type is geometry_msgs/msg/Twist ros2 interface show geometry_msgs/msg/Twist # The linear.x value is what we will want to control
Creating the publisher
from geometry_msgs.msg import Twist, Vector3 # create the publisher in PubsubNode.__init__ self._pub = self.create_publisher(Twist, "cmd_vel", 10) self._velocity = 2.0 # In the timer self._pub.publish(Twist(linear=Vector3(x=self._velocity)))
Verify the message is published at the correct frequency. Includes remapping the topic
# Commands may need to be run in separate terminals or backgrounded ros2 run pubsub pubsub --ros-args -r cmd_vel:=turtle1/cmd_vel ros2 topic hz cmd_vel ros2 topic echo /turtle1/cmd_vel
XML Launchfile
<launch> <node pkg="turtlesim" exec="turtlesim_node" /> <node pkg="pubsub" exec="pubsub"> <remap from="cmd_vel" to="turtle1/cmd_vel" /> </node> </launch>
data_files=[ ('share/ament_index/resource_index/packages', ['resource/' + package_name]), ('share/' + package_name, ['package.xml']), ('share/' + package_name + '/launch', ['launch/pubsub.launch.xml']) ],
Subscriber
To find out about the turtlesim pose:
ros2 topic list ros2 topic info /turtle1/pose ros2 interface show turtlesim/msg/Pose
- Update the launchfile by adding this remapping to the
pubsub
node:<remap from="pose" to="turtle1/pose" />
from turtlesim.msg import Pose # in PubsubNode.__init__: self._sub = self.create_subscription(Pose, "pose", self.pose_callback, 10) # Add the callback def pose_callback(self, pose): """Update the pose of the robot""" if pose.x > 7 and self._velocity > 0: self._velocity *= -1.0 elif pose.x < 2 and self._velocity < 0: self._velocity *= -1.0
Parameters
Custom Parameters
# In PubsubNode.__init__ self.declare_parameter("xmin", 2.0) self._xmin = self.get_parameter("xmin").value self.declare_parameter("xmax", 2.0) self._xmax = self.get_parameter("xmax").value self.get_logger().debug(f"Xmin: {self._xmin} Xmax: {self._xmax}") # Now the subscriber can use self._xmin and self._xmax instead of hard-coded values
Testing the Parameters
To test the node: ros2 run pubsub pubsub --ros-args -p xmin:=3.1 -p xmax:=6.5 --log-level pubsub:=DEBUG
Parameters in launch file
<node pkg="pubsub" exec="pubsub"> <remap from="cmd_vel" to="turtle1/cmd_vel" /> <remap from="pose" to="turtle1/pose" /> <param name="xmin" value="$(var xmin)"/> <param name="xmax" value="$(var xmax)"/> </node>
Namespaces
Changing the Namespace
ros2 run turtlesim turtlesim_node --ros-args -r __ns:=/ns1 ros2 run pubsub pubsub --ros-args -r __ns:=/ns1/turtle1 ros2 run turtlesim turtlesim_node --ros-args -r __ns:=/ns2 ros2 run pubsub pubsub --ros-args -r __ns:=/ns2/turtle1 -p xmin:=1.0 -p xmax:=6.0
Namespace Launchfile
<!-- Command two turtles in two turtle sims --> <launch> <group> <push_ros_namespace namespace="ns1"/> <include file="$(find-pkg-share pubsub)/launch/pubsub.launch.xml" /> </group> <group> <push_ros_namespace namespace="ns2"/> <include file="$(find-pkg-share pubsub)/launch/pubsub.launch.xml" /> </group> </launch>
data_files=[ ('share/ament_index/resource_index/packages', ['resource/' + package_name]), ('share/' + package_name, ['package.xml']), ('share/' + package_name + '/launch', ['launch/pubsub.launch.xml', 'launch/two_pubsub.launch.xml']) ],
Services
Calling the Spawn Service
spawn_client = self.create_client(Spawn, "spawn") if not spawn_client.wait_for_service(timeout_sec = 2.0): raise RuntimeError("Failed to find spawn service.") rclpy.spin_until_future_complete(self, spawn_client.call_async(Spawn.Request(x=self._xmin, y=5.54))) rclpy.spin_until_future_complete(self, spawn_client.call_async(Spawn.Request(x=self._xmax, y=5.54)))
Full Solution
Do you really want to see it?
Are you sure?
The full solution is at https://github.com/m-elwin/me495_pubsub.
Reference
- ROS Basics (and references therein).
- ROS API (and references therein).