Newer
Older
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
#!/usr/bin/env python
#################################################################################
# Copyright 2018 ROBOTIS CO., LTD.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
#################################################################################
# Authors: Gilbert #
import sys
import rospy
import math
from sensor_msgs.msg import LaserScan
from std_msgs.msg import String
from geometry_msgs.msg import Twist
from datetime import datetime
from gazebo_msgs.srv import GetWorldProperties
#Angepasst fuer Log-Aufzeichnung
topic = 'chatter'
pub = rospy.Publisher(topic, String)
LINEAR_VEL = 0.22
STOP_DISTANCE = float(sys.argv[1])
LIDAR_ERROR = 0.05
SAFE_STOP_DISTANCE = STOP_DISTANCE + LIDAR_ERROR
class Obstacle():
def __init__(self):
self._cmd_pub = rospy.Publisher('cmd_vel', Twist, queue_size=1)
self.obstacle()
def get_scan(self):
scan = rospy.wait_for_message('scan', LaserScan)
scan_filter = []
samples = len(scan.ranges) # The number of samples is defined in
# turtlebot3_<model>.gazebo.xacro file,
# the default is 360.
samples_view = 1 # 1 <= samples_view <= samples
if samples_view > samples:
samples_view = samples
if samples_view is 1:
scan_filter.append(scan.ranges[0])
else:
left_lidar_samples_ranges = -(samples_view//2 + samples_view % 2)
right_lidar_samples_ranges = samples_view//2
left_lidar_samples = scan.ranges[left_lidar_samples_ranges:]
right_lidar_samples = scan.ranges[:right_lidar_samples_ranges]
scan_filter.extend(left_lidar_samples + right_lidar_samples)
for i in range(samples_view):
if math.isnan(scan_filter[i]):
scan_filter[i] = 0
return scan_filter
def obstacle(self):
global pub
twist = Twist()
turtlebot_moving = True
while not rospy.is_shutdown():
lidar_distances = self.get_scan()
min_distance = min(lidar_distances)
if min_distance < SAFE_STOP_DISTANCE:
if turtlebot_moving:
twist.linear.x = 0.0
twist.angular.z = 0.0
self._cmd_pub.publish(twist)
turtlebot_moving = False
rospy.loginfo('Stop!')
pub.publish("Stop!")
else:
twist.linear.x = LINEAR_VEL
twist.angular.z = 0.0
self._cmd_pub.publish(twist)
turtlebot_moving = True
rospy.loginfo('Distance of the obstacle : %f', min_distance)
pub.publish("Distance of the obstacle : " + str(min_distance))
def main():
rospy.init_node('turtlebot3_obstacle')
try:
obstacle = Obstacle()
except rospy.ROSInterruptException:
pass
if __name__ == '__main__':
main()