ROS: good practices to code with ROS
In this tutorial, you will learn the good paractices to code with the Robot Operating System (ROS).
We never learn better than an example.
Example of the start test
- To include the developement environment (python in this example).
#!/usr/bin/env python
- To import all the librairies.
import RPi.GPIO as GPIO
import rospy
from geometry_msgs.msg import Point
from std_msgs.msg import Bool, Empty
- To set the global variables.
left = 0
start = 0
step = 1
- To do the basic setup.
GPIO.setwarnings(False) # Ignore warning
GPIO.setmode(GPIO.BOARD) # Use physical pin numbering
pins = [38, 37] # The used pin(s)
#button0 - side - 38
#button1 - start - 37
for pin in pins:
GPIO.setup(pin, GPIO.IN, pull_up_down=GPIO.PUD_DOWN) # Set pins to be an input pin and set initial value to be pulled low (off)
- To define the ROS publishers.
bob_pub = rospy.Publisher('show_bob', Empty, queue_size=10)
nav_pub = rospy.Publisher('required_coords', Point, queue_size=10)
- To definition the functions.
def show_bob():
global bob_pub
bob_pub.publish(Empty())
def is_left():
global left
global step
if GPIO.input(pins[0]) == GPIO.LOW:
left = 1
else:
left = 0
if step == 1:
show_bob()
def is_started():
global start
if GPIO.input(pins[1]) == GPIO.LOW:
start = 1
else:
start = 0
def go_to(x, y):
global nav_pub
nav_pub.publish(Point(x, y, 0))
def step_ok_callback(data):
if data.data == True:
global step
global left
if step == 1:
if left == 1:
go_to(0, -30) # x and y: the coordinates of the left dispenser (1)
else:
go_to(0, 30) # x and y: the coordinates of the right dispenser (1)
if step == 2:
rospy.loginfo("Finished !")
if step > 2:
rospy.loginfo("Anormally finished !")
step += 1
else:
rospy.loginfo("Waiting ...")
- To write the main code.
if __name__ == '__main__':
try:
rospy.init_node("raspberry", anonymous=True)
rospy.Subscriber('curry_arrived', Bool, step_ok_callback)
rate=rospy.Rate(1)
while not rospy.is_shutdown():
is_started()
if start == 1:
is_left()
rospy.loginfo(step)
rate.sleep()
else:
print('Not started')
except rospy.ROSInterruptException:
pass
Explainations of the code
We always check if the start cable is off (if the robot can start).
When it is OK, we check the position of the side button (left or right of the game area) and publish a toggle message on show_bob topic to set the suction cup.
After this move, the first arduino send "True" to the curry_arrived topic and the callback function is launched. An instruction will be sent after each True message recieved on the same topic.