!

Note: This tutorial assumes that you have completed the previous tutorials: writing a simple publisher and subscriber (python).
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Moving in a Straight Line

Description: This tutorial is based on Turtlesim Video Tutorials

Tutorial Level: INTERMEDIATE

Next Tutorial: Rotating Left/Right

In this tutorial series, we will create python scripts to move our turtle, in order to practice the ROS basics.

You can find the complete package at: https://github.com/clebercoutof/turtlesim_cleaner

Preparing for work

First of all, we have to create a new package.

$ cd ~/catkin_ws/src
$ catkin_create_pkg turtlesim_cleaner geometry_msgs rospy

Now, build your workspace

#At your catkin workspace
$ cd ~/catkin_ws
$ catkin_make

And now, create a a src folder for your scripts

$ cd ~/catkin_ws/src/turtlesim_cleaner
$ mkdir src
$ cd ~/catkin_ws
$ catkin_make

Understanding the code

Our code will receive as inputs the desired speed, distance and a variable which defines if the movement is forwards or backwards. Since we can just publish a velocity to the topic /turtle1/cmd_vel, our logic will have to calculate the distance specified.

The code

Create your move.py (or any name you want) file and save it in your ~/catkin_ws/src/turtlesim_cleaner/src, our code will look like this:

   1 #!/usr/bin/env python
   2 import rospy
   3 from geometry_msgs.msg import Twist
   4 
   5 def move():
   6     # Starts a new node
   7     rospy.init_node('robot_cleaner', anonymous=True)
   8     velocity_publisher = rospy.Publisher('/turtle1/cmd_vel', Twist, queue_size=10)
   9     vel_msg = Twist()
  10 
  11     #Receiveing the user's input
  12     print("Let's move your robot")
  13     speed = input("Input your speed:")
  14     distance = input("Type your distance:")
  15     isForward = input("Foward?: ")#True or False
  16 
  17     #Checking if the movement is forward or backwards
  18     if(isForward):
  19         vel_msg.linear.x = abs(speed)
  20     else:
  21         vel_msg.linear.x = -abs(speed)
  22     #Since we are moving just in x-axis
  23     vel_msg.linear.y = 0
  24     vel_msg.linear.z = 0
  25     vel_msg.angular.x = 0
  26     vel_msg.angular.y = 0
  27     vel_msg.angular.z = 0
  28 
  29     while not rospy.is_shutdown():
  30 
  31         #Setting the current time for distance calculus
  32         t0 = rospy.Time.now().to_sec()
  33         current_distance = 0
  34 
  35         #Loop to move the turtle in an specified distance
  36         while(current_distance < distance):
  37             #Publish the velocity
  38             velocity_publisher.publish(vel_msg)
  39             #Takes actual time to velocity calculus
  40             t1=rospy.Time.now().to_sec()
  41             #Calculates distancePoseStamped
  42             current_distance= speed*(t1-t0)
  43         #After the loop, stops the robot
  44         vel_msg.linear.x = 0
  45         #Force the robot to stop
  46         velocity_publisher.publish(vel_msg)
  47 
  48 if __name__ == '__main__':
  49     try:
  50         #Testing our function
  51         move()
  52     except rospy.ROSInterruptException: pass

Don't forget to make your node executable:

$ chmod u+x ~/catkin_ws/src/turtlesim_cleaner/src/move.py

First we need to import the packages used on our script.The rospy library is the ros python library, it contains the basic functions, like creating a node, getting time and creating a publisher.The geometry_msgs contains the variable type Twist that will be used: Error: No code_block found

Now we declare our function, initiate our node, our publisher and create the Twist variable. Error: No code_block found

The Twist is necessary because our topic '/turtle1/cmd_vel' uses the Twist message, you can check with the following command:

$ rostopic info /turtle1/cmd_vel

You should see the following screen:

  • rostopicinfocmdvel.png

The Twist message is composed by 3 linear components and 3 angular components,you can see the message description with the following command:

$ rosmsg show geometry_msgs/Twist

You should see the following screen:

  • rosmsgtwist.png

Since we are moving the turtle in a straight line, we just need the x component, and, depending on the user's input we decide if the movement is forwards or backwards. Error: No code_block found

The following statement guarentee that if we press crtl + c our code will stops Error: No code_block found

Now , with the rospy.Time.now().to_sec(). we get the starting time t0, and the time t1 to calculate the distance and while the actual distance is less than the user's input, it will keep publishing: Error: No code_block found

After we get to the specified distance , we order our robot to stop: Error: No code_block found

And then, we have our main loop which calls our function: Error: No code_block found

Now , you can test and move your robot!

Testing the code

In a new terminal, run:

$ roscore

In a new terminal, run:

$ rosrun turtlesim turtlesim_node

The turtlesim window will open:

  • turtle_spawned.png

Now, in a new terminal, run our code:

$ rosrun turtlesim_cleaner move.py

Just type your inputs and the turtle will move! Here we have an example:

Let's move your robot
Input your speed:1
Type your distance:3
Foward?: 0

The turtle will move like this:

  • turtle_moved.png

Now you can go to the next tutorial! Learn how to rotate your turtle.

Wiki: turtlesim/Tutorials/Moving in a Straight Line (last edited 2019-06-13 21:55:08 by JayEss)