1.9 Publishing to topics#
Although we are able to get some sensordata (as topics) from the robot, and also drive around (by calling services), this might not be the ideal way of driving your robot. In ROS the default of driving around a mobile platform is not by calling services, but by publishing to a topic of the Twist type. As you can see this interface has two components:
Vector3 linear
float64 x
float64 y
float64 z
Vector3 angular
float64 x
float64 y
float64 z
This message type is expressing the velocity of the robot brokin into linear and angular speed (in m/s). For a dirrential drive robot this means we can only use linear.x (forward/backward) and angular.z (turning around its axis).
This also means there needs to be someting (a ROS node) that is listening to a topic with this Twist type. Usually this is a topic with ‘cmd_vel’ (command velocity) in its name. Up till now, we only started the ROS telemtrix node to commuicate with the mictrocontroller. From now on it makes more sense to start the full MIRTE ROS system. To do so, you first need to stop the telemetrix node by pressing CTRL-C in the terminal where we started this node. Only then are we able to start the full MIRTE ROS system:
$ ros2 launch mirte_bringup minimal.launch.py
This will start the telemtrix node, but also some others responsible for controlling the motors. And again you can have a look which nodes are running, find out that the cmd_vel topis is called /diffbot_base_controller/cmd_vel_unstamped.
We again have all the information we need to publish to this topic:
Creating a new node called drive.py
Put the code below in that file
Adding this node to setup.py
Build everything
Start the node
info
For debugging purposes, you can again also send data to this topic from the commandline:
$ ros2 topic pub --once /diffbot_base_controller/cmd_vel_unstamped geometry_msgs/msg/Twist "{linear: {x: 1}}"
1import rclpy
2from rclpy.node import Node
3from geometry_msgs.msg import Twist
4
5class MinimalPublisher(Node):
6 def __init__(self):
7 super().__init__('drive_publisher')
8 self.publisher_ = self.create_publisher(
9 Twist,
10 '/diffbot_base_controller/cmd_vel_unstamped',
11 10)
12 timer_period = 0.5 # seconds
13 self.timer = self.create_timer(timer_period, self.timer_callback)
14
15 def timer_callback(self):
16 msg = Twist()
17 msg.linear.x = 1.0 # m/s
18 self.publisher_.publish(msg)
19 self.get_logger().info('Publishing linear.x: "%f"' % msg.linear.x)
20
21def main(args=None):
22 rclpy.init(args=args)
23 minimal_publisher = MinimalPublisher()
24 rclpy.spin(minimal_publisher)
25 minimal_publisher.destroy_node()
26 rclpy.shutdown()
27
28if __name__ == '__main__':
29 main()