Final version with comments
This commit is contained in:
parent
d7ac5a9f93
commit
d4fae5b3f9
7
map.yaml
7
map.yaml
|
|
@ -1,7 +0,0 @@
|
||||||
image: /home/kilian/map.pgm
|
|
||||||
resolution: 0.050000
|
|
||||||
origin: [-10.000000, -10.000000, 0.000000]
|
|
||||||
negate: 0
|
|
||||||
occupied_thresh: 0.65
|
|
||||||
free_thresh: 0.196
|
|
||||||
|
|
||||||
|
|
@ -1,14 +1,49 @@
|
||||||
#!/usr/bin/env python
|
#!/usr/bin/env python
|
||||||
import rospy
|
#Previous line made to interpret the code in Python
|
||||||
|
|
||||||
|
'''
|
||||||
|
Autopilot script
|
||||||
|
|
||||||
|
ROS script that creates a node called autopilot. This node make a Turtlebot3 have a roomba behavior to ease SLAM process.
|
||||||
|
The robot goes in straight line until an obstacle is detected too close, then turn of a random value and goes in a straight line.
|
||||||
|
The process then store the relative position estimated by the odom topic when received and sum it.
|
||||||
|
When this value outgrows a treshold, the process stops.
|
||||||
|
|
||||||
|
This node subscribes to the topic /scan & /odom
|
||||||
|
This node publishes to the topic /cmd_vel
|
||||||
|
|
||||||
|
author: Kilian Declercq, kilian.declercq@ecam.fr, Thomas Boutant, thomas.boutant@ecam.fr,
|
||||||
|
date: 27/11/2022
|
||||||
|
'''
|
||||||
|
|
||||||
|
#Python imports
|
||||||
import numpy as np
|
import numpy as np
|
||||||
import random
|
import random
|
||||||
|
|
||||||
|
#ROS imports (rospy & msgs type)
|
||||||
|
import rospy
|
||||||
from std_msgs.msg import String
|
from std_msgs.msg import String
|
||||||
from geometry_msgs.msg import Twist
|
from geometry_msgs.msg import Twist
|
||||||
from sensor_msgs.msg import LaserScan
|
from sensor_msgs.msg import LaserScan
|
||||||
from nav_msgs.msg import Odometry
|
from nav_msgs.msg import Odometry
|
||||||
|
|
||||||
distancemin = 0.4
|
# Definition of the constants & variables
|
||||||
inittmp = [0,0]
|
distancemin = 0.4 # Distance of detection at which the robot stops and turn
|
||||||
|
init = [0,0] # Initialisation of position coordinates for callback2
|
||||||
|
dist_covered =[] # Array that store all the covered distances
|
||||||
|
|
||||||
|
|
||||||
|
# ...
|
||||||
|
|
||||||
|
'''
|
||||||
|
Function: publish_move(move):
|
||||||
|
|
||||||
|
Task: Publish a message to the cmd_vel topic
|
||||||
|
|
||||||
|
Inputs:
|
||||||
|
- move: message of type Twist
|
||||||
|
(-pub: could put pub as input to avoid redefining the node publisher at every call of publish_move)
|
||||||
|
'''
|
||||||
|
|
||||||
def publish_move(move):
|
def publish_move(move):
|
||||||
rate = rospy.Rate(10)
|
rate = rospy.Rate(10)
|
||||||
|
|
@ -16,6 +51,21 @@ def publish_move(move):
|
||||||
pub.publish(move)
|
pub.publish(move)
|
||||||
rate.sleep()
|
rate.sleep()
|
||||||
|
|
||||||
|
|
||||||
|
# ...
|
||||||
|
|
||||||
|
'''
|
||||||
|
Function: callback1(move):
|
||||||
|
|
||||||
|
Task: When data is received by the /scan topic, detect if in object in a range of 60° in front of
|
||||||
|
the robot is under the treshold distance.
|
||||||
|
If is not the case, publish a x linear move with publish_move() and print 'forward'
|
||||||
|
If this is the case, publish a z angular move with publish_move() and print 'Turn'
|
||||||
|
|
||||||
|
Inputs:
|
||||||
|
- data: message of type LaserScan
|
||||||
|
'''
|
||||||
|
|
||||||
def callback1(data):
|
def callback1(data):
|
||||||
move = Twist()
|
move = Twist()
|
||||||
distance = min(data.ranges[0:29] and data.ranges[329:359])
|
distance = min(data.ranges[0:29] and data.ranges[329:359])
|
||||||
|
|
@ -32,9 +82,21 @@ def callback1(data):
|
||||||
print('turn')
|
print('turn')
|
||||||
publish_move(move)
|
publish_move(move)
|
||||||
|
|
||||||
dist_covered =[]
|
|
||||||
|
|
||||||
def callback2(data,init = inittmp):
|
# ...
|
||||||
|
|
||||||
|
'''
|
||||||
|
Function: callback2(move):
|
||||||
|
|
||||||
|
Task: When data is received from the odom sensor, compare it to the previous position and extract the travelled distance.
|
||||||
|
Append traveled distance to the dist_covered array. When the sum of the array overcome the treshold value, stop the process.
|
||||||
|
|
||||||
|
Inputs:
|
||||||
|
- data: message of type Odometry
|
||||||
|
'''
|
||||||
|
|
||||||
|
def callback2(data):
|
||||||
|
global init
|
||||||
rate = rospy.Rate(10)
|
rate = rospy.Rate(10)
|
||||||
pos =[data.pose.pose.position.x,data.pose.pose.position.y]
|
pos =[data.pose.pose.position.x,data.pose.pose.position.y]
|
||||||
tmp = np.linalg.norm(np.array(init)-np.array(pos))
|
tmp = np.linalg.norm(np.array(init)-np.array(pos))
|
||||||
|
|
@ -42,7 +104,7 @@ def callback2(data,init = inittmp):
|
||||||
init = pos
|
init = pos
|
||||||
print("The distance covered %s" %sum(dist_covered))
|
print("The distance covered %s" %sum(dist_covered))
|
||||||
|
|
||||||
if sum(dist_covered) >= 20000:
|
if sum(dist_covered) >= 200:
|
||||||
stop = Twist()
|
stop = Twist()
|
||||||
stop.angular.z = 0
|
stop.angular.z = 0
|
||||||
stop.linear.x = 0
|
stop.linear.x = 0
|
||||||
|
|
@ -53,15 +115,30 @@ def callback2(data,init = inittmp):
|
||||||
rate.sleep()
|
rate.sleep()
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
# ...
|
||||||
|
|
||||||
|
'''
|
||||||
|
Function: autopilot():
|
||||||
|
|
||||||
|
Task: Subscribe our autopilot node to /scan & /odom topics, and call respectives callback functions
|
||||||
|
|
||||||
|
Inputs:
|
||||||
|
- data: message of type Odometry
|
||||||
|
- init = inittmp: for the first initialisation of the loop provide an initial array
|
||||||
|
'''
|
||||||
|
|
||||||
def autopilot():
|
def autopilot():
|
||||||
rospy.Subscriber("scan", LaserScan, callback1)
|
rospy.Subscriber("scan", LaserScan, callback1)
|
||||||
rospy.Subscriber("odom", Odometry, callback2)
|
rospy.Subscriber("odom", Odometry, callback2)
|
||||||
rospy.spin()
|
rospy.spin()
|
||||||
|
|
||||||
|
|
||||||
|
# ...
|
||||||
|
|
||||||
if __name__ == '__main__':
|
if __name__ == '__main__':
|
||||||
rospy.init_node('autopilot', anonymous = True)
|
rospy.init_node('autopilot', anonymous = True) # Initialise our node
|
||||||
autopilot()
|
autopilot() # Launch autopilot() function
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue