Moving the Base

Description: This tutorial will show you how to move the robot base.

Tutorial Level: BEGINNER

Next Tutorial: Pointing the Head

Moving the Base via Teleop

The easiest way to move the robot around is using the teleop_twist_keyboard program. CTRL-SHIFT-T will again open another tab in your terminal, in which you can type:

rosrun teleop_twist_keyboard teleop_twist_keyboard.py

You will then be able to drive the robot around using the keyboard. Note that you have to hold down the keys to have messages sent continuously, otherwise the robot stops (this is a safety feature).

Moving the Base with Your Own Code

The tele-operation node wasn't magic. In fact, if you leave it running, you could run rxgraph and see that the teleop_twist_keyboard node is publishing to a topic called cmd_vel, to which the iRobot Create node is subscribing. We can of course publish our own commands to cmd_vel. The remainder of this tutorial will walk through doing this.

Understanding cmd_vel

The cmd_vel message is of type geometry_msgs/Twist. The expanded definition looks like:

Vector3 linear
    float64 x
    float64 y
    float64 z
Vector3 angular
    float64 x
    float64 y
    float64 z

However, our robot can't drive sideways (linear.y), or rotate about the x-axis! Therefore, we will only be using linear.x and angular.z to control our robot.

Moving Forward for 3 Seconds

Our first example will move the robot forward for 3 seconds:

https://vanadium-ros-pkg.googlecode.com/svn/trunk/mini_max/mini_max_tutorials/nodes/move.py

   1 #!/usr/bin/env python
   2 
   3 """ Example code of how to move a robot forward for 3 seconds. """
   4 
   5 # We always import roslib, and load the manifest to handle dependencies
   6 import roslib; roslib.load_manifest('mini_max_tutorials')
   7 import rospy
   8 
   9 # recall: robots generally take base movement commands on a topic 
  10 #  called "cmd_vel" using a message type "geometry_msgs/Twist"
  11 from geometry_msgs.msg import Twist
  12 
  13 x_speed = 0.1  # 0.1 m/s
  14 
  15 # this quick check means that the following code runs ONLY if this is the 
  16 # main file -- if we "import move" in another file, this code will not execute.
  17 if __name__=="__main__":
  18 
  19     # first thing, init a node!
  20     rospy.init_node('move')
  21 
  22     # publish to cmd_vel
  23     p = rospy.Publisher('cmd_vel', Twist)
  24 
  25     # create a twist message, fill in the details
  26     twist = Twist()
  27     twist.linear.x = x_speed;                   # our forward speed
  28     twist.linear.y = 0; twist.linear.z = 0;     # we can't use these!        
  29     twist.angular.x = 0; twist.angular.y = 0;   #          or these!
  30     twist.angular.z = 0;                        # no rotation
  31 
  32     # announce move, and publish the message
  33     rospy.loginfo("About to be moving forward!")
  34     for i in range(30):
  35         p.publish(twist)
  36         rospy.sleep(0.1) # 30*0.1 = 3.0
  37 
  38     # create a new message
  39     twist = Twist()
  40 
  41     # note: everything defaults to 0 in twist, if we don't fill it in, we stop!
  42     rospy.loginfo("Stopping!")
  43     p.publish(twist)

Here we create a twist message, fill in the forward velocity, and publish it. As long as Mini Maxwell is running, he should move forward (slowly) for about 3 seconds. The second twist message contains all 0 velocities, and thus stops the robot. By convention, in ROS, all linear velocities are given in meters per second, and rotations in radians per second.

Drawing a Square Until Shutdown

We'll now try a more complex example, which involves multiple moves, turning, and cleaning up on shutdown.

https://vanadium-ros-pkg.googlecode.com/svn/trunk/mini_max/mini_max_tutorials/nodes/square.py

   1 #!/usr/bin/env python
   2 
   3 """ Example code of how to move a robot around the shape of a square. """
   4 
   5 # We always import roslib, and load the manifest to handle dependencies
   6 import roslib; roslib.load_manifest('mini_max_tutorials')
   7 import rospy
   8 
   9 # recall: robots generally take base movement commands on a topic 
  10 #  called "cmd_vel" using a message type "geometry_msgs/Twist"
  11 from geometry_msgs.msg import Twist
  12 
  13 class square:
  14     """ This example is in the form of a class. """
  15 
  16     def __init__(self):
  17         """ This is the constructor of our class. """
  18         # register this function to be called on shutdown
  19         rospy.on_shutdown(self.cleanup)
  20 
  21         # publish to cmd_vel
  22         self.pub = rospy.Publisher('cmd_vel', Twist)
  23         # give our node/publisher a bit of time to connect
  24         rospy.sleep(1)
  25 
  26         # use a rate to make sure the bot keeps moving
  27         r = rospy.Rate(5.0)
  28 
  29         # go forever!
  30         while not rospy.is_shutdown():
  31             # create a Twist message, fill it in to drive forward
  32             twist = Twist()
  33             twist.linear.x = 0.15
  34             for i in range(10):         # 10*5hz = 2sec
  35                 self.pub.publish(twist)
  36                 r.sleep()
  37             # create a twist message, fill it in to turn
  38             twist = Twist()
  39             twist.angular.z = 1.57/2    # 45 deg/s * 2sec = 90 degrees
  40             for i in range(10):         # 10*5hz = 2sec
  41                 self.pub.publish(twist)
  42                 r.sleep()
  43 
  44     def cleanup(self):
  45         # stop the robot!
  46         twist = Twist()
  47         self.pub.publish(twist)
  48 
  49 if __name__=="__main__":
  50     rospy.init_node('square')
  51     square()

As before, we create Twist messages and publish them. This example uses a Python class, which is a good idea for easily storing publishers which may be used again.

A More Accurate Square Using TF (Advanced)

Wiki: mini_max/Tutorials/Moving the Base (last edited 2011-09-08 08:10:40 by MichaelFerguson)