Teleoperate Stretch with a Node
Example 1
Note
ROS 2 tutorials are still under active development.
The goal of this example is to give you an enhanced understanding of how to control the mobile base by sending Twist
messages to a Stretch robot.
ros2 launch stretch_core stretch_driver.launch.py
To drive the robot in circles with the move node, type the following in a new terminal.
ros2 run stetch_ros_tutorials move
The Code
Below is the code which will send Twist messages to drive the robot in circles.
#!/usr/bin/env python3
import rclpy
from rclpy.node import Node
from geometry_msgs.msg import Twist
class Move(Node):
def __init__(self):
super().__init__('stretch_base_move')
self.publisher_ = self.create_publisher(Twist, '/stretch/cmd_vel', 10)
self.get_logger().info("Starting to move in circle...")
timer_period = 0.5 # seconds
self.timer = self.create_timer(timer_period, self.move_around)
def move_around(self):
command = Twist()
command.linear.x = 0.0
command.linear.y = 0.0
command.linear.z = 0.0
command.angular.x = 0.0
command.angular.y = 0.0
command.angular.z = 0.5
self.publisher_.publish(command)
def main(args=None):
rclpy.init(args=args)
base_motion = Move()
rclpy.spin(base_motion)
base_motion.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
The Code Explained
Now let's break the code down.
#!/usr/bin/env python3
import rclpy
from rclpy.node import Node
from geometry_msgs.msg import Twist
class Move(Node):
def __init__(self):
super().__init__('stretch_base_move')
self.publisher_ = self.create_publisher(Twist, '/stretch/cmd_vel', 10)
timer_period = 0.5 # seconds
self.timer = self.create_timer(timer_period, self.move_around)
command = Twist()
command.linear.x = 0.0
command.linear.y = 0.0
command.linear.z = 0.0
command.angular.x = 0.0
command.angular.y = 0.0
command.angular.z = 0.5
self.publisher_.publish(command)
def main(args=None):
rclpy.init(args=args)
base_motion = Move()
rclpy.spin(base_motion)
base_motion.destroy_node()
rclpy.shutdown()
To stop the node from sending twist messages, type Ctrl + c
.