Skip to content

Commit

Permalink
Modified guidance algorithim
Browse files Browse the repository at this point in the history
  • Loading branch information
abubakaraliyubadawi committed Oct 9, 2024
1 parent 2cee34d commit 917d5bf
Show file tree
Hide file tree
Showing 179 changed files with 5,535 additions and 0 deletions.
Empty file.
150 changes: 150 additions & 0 deletions guidance/guidance_pkg/guidance_pkg/guidance.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,150 @@
import rclpy
from rclpy.node import Node
from std_msgs.msg import Float32MultiArray
from nav_msgs.msg import Odometry
import numpy as np
import math
from transforms3d.euler import quat2euler

class GuidanceNode(Node):
def __init__(self):
super().__init__('guidance_pkg')

# Publisher to output the surge velocity, pitch angle, and heading angle
self.output_pub = self.create_publisher(Float32MultiArray, '/guidance/waypoints', 10)

# Subscriber to receive odometry data from '/nucleus/odom'
self.create_subscription(Odometry, '/nucleus/odom', self.odom_callback, 10)

# Initialize variables
self.current_position = None
self.current_velocity = None
self.current_orientation = None

# Parameters for the guidance algorithm
self.U = 1.0 # Desired speed
self.delta = 1.2 # Lookahead distance

# Define waypoints as a list of dictionaries with x, y, z coordinates
self.waypoints = [
{'x': 5.0, 'y': -5.0, 'z': -8.0},
{'x': 10.0, 'y': 5.0, 'z': -5.0},
{'x': 15.0, 'y': 0.0, 'z': 0.0},
# Add more waypoints as needed
]
self.current_waypoint_index = 0

# Timer to periodically run the guidance algorithm
self.create_timer(0.1, self.timer_callback)

def odom_callback(self, msg):
"""
Callback function to process odometry data.
"""
self.current_position = msg.pose.pose.position
self.current_velocity = msg.twist.twist.linear
orientation_q = msg.pose.pose.orientation

# Convert quaternion to Euler angles
# ROS quaternion format: (x, y, z, w)
quaternion = [orientation_q.w, orientation_q.x, orientation_q.y, orientation_q.z]
roll, pitch, yaw = quat2euler(quaternion)
self.current_orientation = {'roll': roll, 'pitch': pitch, 'yaw': yaw}

def timer_callback(self):
"""
Timer callback to compute and publish guidance commands.
"""
if self.current_position is None or self.current_orientation is None:
# Wait until odometry data is received
return

if self.current_waypoint_index >= len(self.waypoints):
# All waypoints have been reached
self.get_logger().info('All waypoints reached.')
return

# Get the current waypoint
waypoint = self.waypoints[self.current_waypoint_index]

# Extract current position
current_x = self.current_position.x
current_y = self.current_position.y
current_z = self.current_position.z

# Extract current orientation
psi = self.current_orientation['yaw'] # Heading angle
theta = self.current_orientation['pitch'] # Pitch angle

# Extract target waypoint position
target_x = waypoint['x']
target_y = waypoint['y']
target_z = waypoint['z']

# Compute distance to the waypoint
distance = math.sqrt(
(target_x - current_x) ** 2 +
(target_y - current_y) ** 2 +
(target_z - current_z) ** 2
)

# Check if the waypoint is reached
if distance < 0.5:
self.get_logger().info(f'Reached waypoint {self.current_waypoint_index}')
self.current_waypoint_index += 1
if self.current_waypoint_index >= len(self.waypoints):
self.get_logger().info('All waypoints reached.')
return
else:
waypoint = self.waypoints[self.current_waypoint_index]

# Guidance calculations using a Line-of-Sight (LOS) algorithm
ref_x = current_x
ref_y = current_y
ref_z = current_z

dx = target_x - ref_x
dy = target_y - ref_y
dz = target_z - ref_z

# Compute desired heading angle (psi_d)
pi_p = math.atan2(dy, dx)
pi_p = normalize_angle(pi_p)

# Compute desired pitch angle (theta_d)
gamma = math.atan2(-dz, math.hypot(dx, dy))

# Compute cross-track error
e_ct = -(dx * (current_y - ref_y) - dy * (current_x - ref_x)) / math.hypot(dx, dy)

# Compute desired course angle
course_d = pi_p - math.atan(e_ct / self.delta)
course_d = normalize_angle(course_d)

# Set desired surge velocity
surge_velocity = self.U

# Set desired heading and pitch angles
heading_angle = course_d
pitch_angle = gamma

# Prepare and publish the output message
output_msg = Float32MultiArray()
output_msg.data = [surge_velocity, pitch_angle, heading_angle]
self.output_pub.publish(output_msg)

def normalize_angle(angle):
"""
Normalize an angle to the range [-π, π].
"""
return (angle + np.pi) % (2 * np.pi) - np.pi

def main(args=None):
rclpy.init(args=args)
node = GuidanceNode()
rclpy.spin(node)
node.destroy_node()
rclpy.shutdown()

if __name__ == '__main__':
main()
32 changes: 32 additions & 0 deletions guidance/guidance_pkg/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
<?xml version="1.0"?>
<package format="3">
<name>guidance_pkg</name>
<version>0.0.0</version>
<description>Package for guidance node implementing PID control.</description>
<maintainer email="badawi@todo.todo">badawi</maintainer>
<license>TODO: License declaration</license>

<!-- Build tool dependency -->
<buildtool_depend>ament_python</buildtool_depend>

<!-- Build dependencies -->
<build_depend>rclpy</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>nav_msgs</build_depend>

<!-- Execution dependencies -->
<exec_depend>rclpy</exec_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>nav_msgs</exec_depend>
<exec_depend>tf_transformations</exec_depend>

<!-- Test dependencies -->
<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>
Empty file.
4 changes: 4 additions & 0 deletions guidance/guidance_pkg/setup.cfg
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
[develop]
script_dir=$base/lib/guidance_pkg
[install]
install_scripts=$base/lib/guidance_pkg
26 changes: 26 additions & 0 deletions guidance/guidance_pkg/setup.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
from setuptools import find_packages, setup

package_name = 'guidance_pkg'

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='badawi',
maintainer_email='badawi@todo.todo',
description='TODO: Package description',
license='TODO: License declaration',
tests_require=['pytest'],
entry_points={
'console_scripts': [
'guidance = guidance_pkg.guidance:main',
],
},
)
25 changes: 25 additions & 0 deletions guidance/guidance_pkg/test/test_copyright.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
# 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'
25 changes: 25 additions & 0 deletions guidance/guidance_pkg/test/test_flake8.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
# 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)
23 changes: 23 additions & 0 deletions guidance/guidance_pkg/test/test_pep257.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
# 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'
Loading

0 comments on commit 917d5bf

Please sign in to comment.