Skip to content
Snippets Groups Projects
Commit 898eebee authored by eber03's avatar eber03
Browse files

Add obstacle avoidance

parent fad33d96
No related branches found
No related tags found
No related merge requests found
#!/usr/bin/env python3
import rclpy
from rclpy.node import Node
from math import isinf
from sensor_msgs.msg import LaserScan
from autominy_msgs.msg import SpeedCommand, NormalizedSteeringCommand
class obstacleAvoidance(Node):
def __init__(self):
super().__init__("obstacle_avoidance")
self.lidar_sub = self.create_subscription(LaserScan, "/sensors/rplidar/scan", self.lidar_callback, 10)
self.speed_pub = self.create_publisher(SpeedCommand, "actuators/speed", 10)
self.steering_pub = self.create_publisher(NormalizedSteeringCommand, "actuators/steering_normalized", 10)
def lidar_callback(self, msg):
distances = msg.ranges
front_distance_min = min(distances[:15] + distances[-15:])
front_left_distance_mean = sum(distances[:30]) / 30
front_right_distance_mean = sum(distances[-30:]) / 30
if front_distance_min < 1 and front_right_distance_mean <= front_left_distance_mean:
steering_angle = 0.8
elif front_distance_min < 1 and front_left_distance_mean < front_right_distance_mean:
steering_angle = -0.8
else:
steering_angle = 0.0
steering_cmd = NormalizedSteeringCommand()
steering_cmd.value = steering_angle
steering_cmd.header.stamp = self.get_clock().now().to_msg()
self.steering_pub.publish(steering_cmd)
self.get_logger().info(f'Publish steering: {steering_angle}')
min_distance = min(distances)
if min_distance <= 0 or isinf(min_distance):
speed = 0.0
else:
speed = 0.3
speed_cmd = SpeedCommand()
speed_cmd.value = speed
speed_cmd.header.stamp = self.get_clock().now().to_msg()
self.speed_pub.publish(speed_cmd)
def main(args = None):
rclpy.init(args=args)
node = obstacleAvoidance()
rclpy.spin(node)
node.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>obstacle_avoidance</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="eber03@zedat.fu-berlin.de">rebecca</maintainer>
<license>TODO: License declaration</license>
<test_depend>ament_copyright</test_depend>
<test_depend>ament_flake8</test_depend>
<test_depend>ament_pep257</test_depend>
<test_depend>python3-pytest</test_depend>
<export>
<build_type>ament_python</build_type>
</export>
</package>
[develop]
script_dir=$base/lib/obstacle_avoidance
[install]
install_scripts=$base/lib/obstacle_avoidance
from setuptools import find_packages, setup
package_name = 'obstacle_avoidance'
setup(
name=package_name,
version='0.0.0',
packages=find_packages(exclude=['test']),
data_files=[
('share/ament_index/resource_index/packages',
['resource/' + package_name]),
('share/' + package_name, ['package.xml']),
],
install_requires=['setuptools'],
zip_safe=True,
maintainer='rebecca',
maintainer_email='eber03@zedat.fu-berlin.de',
description='TODO: Package description',
license='TODO: License declaration',
tests_require=['pytest'],
entry_points={
'console_scripts': [
'obstacle_avoidance = obstacle_avoidance.obstacle_avoidance:main'
],
},
)
# Copyright 2015 Open Source Robotics Foundation, Inc.
#
# 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.
from ament_copyright.main import main
import pytest
# Remove the `skip` decorator once the source file(s) have a copyright header
@pytest.mark.skip(reason='No copyright header has been placed in the generated source file.')
@pytest.mark.copyright
@pytest.mark.linter
def test_copyright():
rc = main(argv=['.', 'test'])
assert rc == 0, 'Found errors'
# Copyright 2017 Open Source Robotics Foundation, Inc.
#
# 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.
from ament_flake8.main import main_with_errors
import pytest
@pytest.mark.flake8
@pytest.mark.linter
def test_flake8():
rc, errors = main_with_errors(argv=[])
assert rc == 0, \
'Found %d code style errors / warnings:\n' % len(errors) + \
'\n'.join(errors)
# Copyright 2015 Open Source Robotics Foundation, Inc.
#
# 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.
from ament_pep257.main import main
import pytest
@pytest.mark.linter
@pytest.mark.pep257
def test_pep257():
rc = main(argv=['.', 'test'])
assert rc == 0, 'Found code style errors / warnings'
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment