Publish to wheels
Contents
Publish to wheels#
What you will need
A Duckietown robot turned ON and visible on
dts fleet discover
What you will get
Learn how to control the Duckiebot’s wheels using a ROS Publisher
Topic and message type of interest#
The Duckiebot subscribes to wheel commands on the topic:
/ROBOT_NAME/wheels_driver_node/wheels_cmd
The message type is duckietown_msgs/WheelsCmdStamped, with fields:
std_msgs/Header header
float32 vel_left
float32 vel_right
header
: standard ROS headervel_left
: duty cycle for left wheel (−1.0 backward to 1.0 forward)vel_right
: duty cycle for right wheel (−1.0 backward to 1.0 forward)
Note
These values represent PWM duty cycles, not physical velocities, and may vary across motors.
Create Publisher ROS Node#
Create wheel_control_node.py
in the src/
directory of the Catkin package:
#!/usr/bin/env python3
import os
import rospy
from duckietown.dtros import DTROS, NodeType
from duckietown_msgs.msg import WheelsCmdStamped
# throttle and direction for each wheel
THROTTLE_LEFT = 0.5 # 50% throttle
DIRECTION_LEFT = 1 # forward
THROTTLE_RIGHT = 0.3 # 30% throttle
DIRECTION_RIGHT = -1 # backward
class WheelControlNode(DTROS):
def __init__(self, node_name):
super(WheelControlNode, self).__init__(
node_name=node_name,
node_type=NodeType.GENERIC
)
vehicle_name = os.environ['VEHICLE_NAME']
wheels_topic = f"/{vehicle_name}/wheels_driver_node/wheels_cmd"
self._vel_left = THROTTLE_LEFT * DIRECTION_LEFT
self._vel_right = THROTTLE_RIGHT * DIRECTION_RIGHT
self._publisher = rospy.Publisher(wheels_topic, WheelsCmdStamped, queue_size=1)
def run(self):
rate = rospy.Rate(0.1)
message = WheelsCmdStamped(vel_left=self._vel_left, vel_right=self._vel_right)
while not rospy.is_shutdown():
self._publisher.publish(message)
rate.sleep()
def on_shutdown(self):
stop = WheelsCmdStamped(vel_left=0, vel_right=0)
self._publisher.publish(stop)
if __name__ == '__main__':
node = WheelControlNode(node_name='wheel_control_node')
node.run()
rospy.spin()
Make it executable:
chmod +x ./packages/my_package/src/wheel_control_node.py
Define launcher#
Create launchers/wheel-control.sh
:
#!/bin/bash
source /environment.sh
dt-launchfile-init
rosrun my_package wheel_control_node.py
dt-launchfile-join
Rebuild the image:
dts devel build -f
Launch the node#
Danger
The wheels will start spinning immediately. Ensure the robot has enough clear space to avoid accidents.
Run the node:
dts devel run -R ROBOT_NAME -L wheel-control
Stop with Ctrl+C
; on_shutdown()
will halt the wheels.
Congratulations 🎉
You just built and ran a ROS node that controls the Duckiebot’s wheels.