Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

436 task guidance node for autopilot #502

Open
wants to merge 54 commits into
base: develop
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 40 commits
Commits
Show all changes
54 commits
Select commit Hold shift + click to select a range
917d5bf
Modified guidance algorithim
Oct 9, 2024
cd4d076
Automated autoyapf fixes
invalid-email-address Oct 9, 2024
7845070
added guidance action server
Oct 11, 2024
7157c5c
Resolved merge conflict in guidance.py
Oct 11, 2024
d7dd424
Automated autoyapf fixes
invalid-email-address Oct 11, 2024
cb2e138
Remove unwanted folder
Oct 11, 2024
0e8585a
Merge remote-tracking branch 'origin/436-task-guidance-node-for-autop…
Oct 11, 2024
6ab5edf
Develop (#487)
kluge7 Oct 13, 2024
cd7f490
Fix errors of no executable
Oct 13, 2024
29c1ad3
trying to resolve merge
Oct 13, 2024
07261ee
Automated autoyapf fixes
invalid-email-address Oct 13, 2024
1fb8b90
Made changes to guidance_action_server and guidance_los files
Oct 21, 2024
d694e89
update guidance action server
Oct 21, 2024
a007e80
Automated autoyapf fixes
invalid-email-address Oct 21, 2024
05ff163
Delete unnecessary files.
Oct 21, 2024
f44e105
modification of the guidance
Oct 23, 2024
9ca5b31
Fixed auto-pilot
Oct 27, 2024
15fed69
Automated autoyapf fixes
invalid-email-address Oct 27, 2024
46455e6
intermediate commit
Nov 3, 2024
9e7d7ba
Merge remote-tracking branch 'origin/485-task-auv-gui' into 436-task-…
Nov 3, 2024
fc4780a
feat: create guidance action server
Nov 10, 2024
79a48b2
Merge remote-tracking branch 'origin/develop' into 436-task-guidance-…
Nov 10, 2024
acc38cb
Merge remote-tracking branch 'origin/develop' into 436-task-guidance-…
Nov 10, 2024
bc076c6
fix(gui): resolve merge conflict in auv_gui.py, retain local updates
kluge7 Nov 11, 2024
9b49170
Modified LOS guidance action server with proper comments and doc strings
Nov 16, 2024
2e9e1c8
Added comprehensive docstrings and comments to LOS guidance algorithm
Nov 16, 2024
d1987fa
change LOS guidance to use third order low-pass filter
Nov 17, 2024
ab21880
fix: vortex_msgs develop branch is target
Hallfred Nov 17, 2024
fa599fe
fix: added pyqt install script
Hallfred Nov 17, 2024
b695f1d
fix: correct ref
Hallfred Nov 17, 2024
03bb8d3
feat: removed tests
Hallfred Nov 17, 2024
992487d
refactor: applied formatting changes
Nov 17, 2024
a4700f8
add stuff
Nov 17, 2024
6ad96af
added stuff
Nov 17, 2024
a78dc87
added stuff
Nov 17, 2024
1bfc2ee
Fixed filter and remove tuple
Nov 17, 2024
e614471
fix CMaklists
Nov 17, 2024
d0061dc
Modified package.xml
Nov 17, 2024
aa27f9f
remove unnecessary comments and added a readme.md file and a yaml fil…
Dec 22, 2024
fd6db80
Apply pre-commit hook fixes
Dec 26, 2024
2f4cfa9
Modified guidance action server node.
Dec 28, 2024
2d4cadf
modify action server and launch file
Jan 2, 2025
8ba17ba
working guidance action server
Jan 7, 2025
3160f92
added goal callback
Jan 7, 2025
afb0a89
added cancel request
Jan 7, 2025
845e362
[pre-commit.ci] auto fixes from pre-commit.com hooks
pre-commit-ci[bot] Jan 7, 2025
62b1fd8
refactor guidance action server
Jan 7, 2025
3b5c8d9
[pre-commit.ci] auto fixes from pre-commit.com hooks
pre-commit-ci[bot] Jan 7, 2025
f748524
feat: remove dependency on transforms3d
Andeshog Jan 8, 2025
87309ba
refactor: remove try-except block
Andeshog Jan 8, 2025
13d1e6f
refactor: correctly initialize new commands after new goal request
Andeshog Jan 8, 2025
e6e3e9f
modified guidance algorithm
Jan 8, 2025
927b03a
[pre-commit.ci] auto fixes from pre-commit.com hooks
pre-commit-ci[bot] Jan 8, 2025
3b80ce0
[pre-commit.ci] auto fixes from pre-commit.com hooks
Hallfred Jan 9, 2025
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 2 additions & 1 deletion .github/workflows/source-build.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -12,5 +12,6 @@ jobs:
with:
ros_distro: 'humble'
os_name: 'ubuntu-22.04'
ref: ${{ github.ref_name }}
ref: ${{ github.ref }}
vcs_repo_file_url: 'https://raw.githubusercontent.com/vortexntnu/vortex-auv/main/ros2.repos'
dependency_script: 'requirements.sh'
1 change: 0 additions & 1 deletion .pre-commit-config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,6 @@ repos:
"--select=D",
"--ignore=D100,D101,D102,D103,D104,D105,D106,D107,D401",
"--fix",
"--unsafe-fixes"
]
stages: [pre-commit]
pass_filenames: true
Expand Down
28 changes: 28 additions & 0 deletions guidance/guidance_los/CMakeLists.txt
AbubakarAliyuBadawi marked this conversation as resolved.
Show resolved Hide resolved
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
cmake_minimum_required(VERSION 3.8)
project(guidance_los)

find_package(ament_cmake_python REQUIRED)
find_package(rclpy REQUIRED)
find_package(std_msgs REQUIRED)
find_package(nav_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(vortex_msgs REQUIRED)

ament_python_install_package(${PROJECT_NAME})

install(
PROGRAMS
scripts/los_guidance_action_server.py
RENAME
los_guidance_action_server
DESTINATION lib/${PROJECT_NAME}
)

install(
DIRECTORY
launch
config
DESTINATION share/${PROJECT_NAME}
)

ament_package()
1 change: 1 addition & 0 deletions guidance/guidance_los/README.md
AbubakarAliyuBadawi marked this conversation as resolved.
Show resolved Hide resolved
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Finish the README

Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
#TODO
30 changes: 30 additions & 0 deletions guidance/guidance_los/config/los_guidance_params.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
los_guidance_node:
# Node configurations
ros__parameters:
los_guidance:
h_delta_min: 1.0
h_delta_max: 5.0
h_delta_factor: 3.0
nominal_speed: 0.35
min_speed: 0.1
max_pitch_angle: 0.52359877559
depth_gain: 0.5
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

add update period dt here, since it is the same for both the node and the calculator

filter:
omega_diag: [2.5, 2.5, 2.5]
zeta_diag: [0.7, 0.7, 0.7]

# Topic configurations
topics:
publishers:
los_commands: '/guidance/LOS_commands'
debug:
reference: '/guidance/debug/reference'
errors: '/guidance/debug/errors'
logs: '/guidance/debug/logs'
subscribers:
odometry: '/nucleus/odom'

# QoS configurations
qos:
publisher_depth: 10
subscriber_depth: 10
AbubakarAliyuBadawi marked this conversation as resolved.
Show resolved Hide resolved
Empty file.
114 changes: 114 additions & 0 deletions guidance/guidance_los/guidance_los/los_guidance_algorithm.py
AbubakarAliyuBadawi marked this conversation as resolved.
Show resolved Hide resolved
AbubakarAliyuBadawi marked this conversation as resolved.
Show resolved Hide resolved
Original file line number Diff line number Diff line change
@@ -0,0 +1,114 @@
#!/usr/bin/env python3
AbubakarAliyuBadawi marked this conversation as resolved.
Show resolved Hide resolved

import numpy as np


class ThirdOrderLOSGuidance:
"""Line-of-Sight (LOS) guidance algorithm."""
AbubakarAliyuBadawi marked this conversation as resolved.
Show resolved Hide resolved

def __init__(self, config_dict: dict):
# Initialize parameters
self.h_delta_min = config_dict['h_delta_min']
self.h_delta_max = config_dict['h_delta_max']
self.h_delta_factor = config_dict['h_delta_factor']
self.nominal_speed = config_dict['nominal_speed']
self.min_speed = config_dict['min_speed']
self.max_pitch_angle = config_dict['max_pitch_angle']
self.depth_gain = config_dict['depth_gain']

# Filter parameters
self.x = np.zeros(9)
self.omega = np.diag(config_dict['filter']['omega_diag'])
self.zeta = np.diag(config_dict['filter']['zeta_diag'])

# Initialize filter matrices
self.setup_filter_matrices()
AbubakarAliyuBadawi marked this conversation as resolved.
Show resolved Hide resolved

def setup_filter_matrices(self):
self.Ad = np.zeros((9, 9))
self.Bd = np.zeros((9, 3))

# Fill Ad matrix blocks
self.Ad[0:3, 3:6] = np.eye(3)
self.Ad[3:6, 6:9] = np.eye(3)

# Compute characteristic polynomial coefficients
omega_cubed = self.omega @ self.omega @ self.omega
omega_squared = self.omega @ self.omega

# Fill in the acceleration dynamics
self.Ad[6:9, 0:3] = -omega_cubed
self.Ad[6:9, 3:6] = -(2 * self.zeta + np.eye(3)) @ omega_squared
self.Ad[6:9, 6:9] = -(2 * self.zeta + np.eye(3)) @ self.omega

# Input matrix
self.Bd[6:9, :] = omega_cubed
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Since this is a one time call, you could extract omega and zeta at the top

def setup_filter_matrices(self):
        omega = np.diag(self.filter_params.omega_diag)
        zeta = np.diag(self.filter_params.zeta_diag)
        omega_cubed = omega @ omega @ omega
        omega_squared = omega @ omega

        self.Ad = np.zeros((9, 9))
        self.Bd = np.zeros((9, 3))

        self.Ad[0:3, 3:6] = np.eye(3)
        self.Ad[3:6, 6:9] = np.eye(3)
        self.Ad[6:9, 0:3] = -omega_cubed
        self.Ad[6:9, 3:6] = -(2 * zeta + np.eye(3)) @ omega_squared
        self.Ad[6:9, 6:9] = -(2 * zeta + np.eye(3)) @ omega

        self.Bd[6:9, :] = omega_cubed


def ssa(self, angle: float) -> float:
return (angle + np.pi) % (2 * np.pi) - np.pi
AbubakarAliyuBadawi marked this conversation as resolved.
Show resolved Hide resolved

def compute_raw_los_guidance(
self, current_pos: np.ndarray, target_pos: np.ndarray
) -> tuple[np.ndarray, float, float]:
# Extract positions
dx = target_pos[0] - current_pos[0]
dy = target_pos[1] - current_pos[1]

# Horizontal plane calculations
horizontal_distance = np.sqrt(dx**2 + dy**2)
desired_yaw = np.arctan2(dy, dx)
yaw_error = self.ssa(desired_yaw - current_pos[3])

# Vertical plane calculations
depth_error = target_pos[2] - current_pos[2]
desired_pitch = self.compute_pitch_command(depth_error, horizontal_distance)

# Compute desired surge velocity
desired_surge = self.compute_desired_speed(yaw_error, horizontal_distance)

# Return commands as numpy array
commands = np.array([desired_surge, desired_pitch, desired_yaw])
return commands, horizontal_distance, depth_error
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Returning horizontal_distance and depth_error here is not necessary. If you need to access them in your debug logs, then just define them as

self.horizontal_distance = ...
self.depth_error = ...

Also, I still feel like taking advantage of the State class would make this method more readable as mentioned here.

For that you would need to move the State class over to this file, and import it with the rest in the action server file.


def compute_pitch_command(
self, depth_error: float, horizontal_distance: float
) -> float:
"""Compute pitch command with distance-based scaling."""
raw_pitch = -self.depth_gain * depth_error
distance_factor = min(1.0, horizontal_distance / self.h_delta_max)
modified_pitch = raw_pitch * distance_factor
return np.clip(modified_pitch, -self.max_pitch_angle, self.max_pitch_angle)

def compute_desired_speed(self, yaw_error: float, distance: float) -> float:
"""Compute speed command with yaw and distance-based scaling."""
yaw_factor = np.cos(yaw_error)
distance_factor = min(1.0, distance / self.h_delta_max)
desired_speed = self.nominal_speed * yaw_factor * distance_factor
return max(self.min_speed, desired_speed)

def apply_reference_filter(self, commands: np.ndarray, dt: float) -> np.ndarray:
# Update filter state
x_dot = self.Ad @ self.x + self.Bd @ commands
self.x = self.x + x_dot * dt
return self.x[0:3] # Return position states [surge, pitch, yaw]

def compute_guidance(
self, current_pos: np.ndarray, target_pos: np.ndarray, dt: float
) -> np.ndarray:
# Compute raw LOS guidance
(
raw_commands,
self.horizontal_distance_to_target,
self.vertical_distance_to_target,
) = self.compute_raw_los_guidance(current_pos, target_pos)

# Apply reference filter
filtered_commands = self.apply_reference_filter(raw_commands, dt)
filtered_commands[2] = self.ssa(filtered_commands[2])
return filtered_commands
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Ref


def reset_filter_state(self, current_commands: np.ndarray) -> None:
self.x = np.zeros(9)
self.x[0:3] = current_commands
self.x[3:6] = np.zeros(3)
self.x[6:9] = np.zeros(3)
42 changes: 42 additions & 0 deletions guidance/guidance_los/launch/guidance.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
import os

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node


def generate_launch_description():
# Get the package share directory
pkg_share = get_package_share_directory('guidance_los')

# Build the config file path
config_file = os.path.join(pkg_share, 'config', 'los_guidance_params.yaml')

# Verify config file exists
if not os.path.exists(config_file):
raise FileNotFoundError(f"Config file not found at: {config_file}")

# Create the launch configuration variables
config_path_arg = DeclareLaunchArgument(
'config_path',
default_value=config_file,
description='/home/badawi/Desktop/auto-pilot/src/vortex-auv/guidance/guidance_los/config/los_guidance_params.yaml',
)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

why do you have this here?


# Create the node
guidance_node = Node(
package='guidance_los',
executable='los_guidance_action_server',
name='guidance_action_server',
output='screen',
emulate_tty=True,
parameters=[
{'config_path': LaunchConfiguration('config_path'), 'debug_mode': False}
],
respawn=False,
)

# Return the launch description
return LaunchDescription([config_path_arg, guidance_node])
22 changes: 22 additions & 0 deletions guidance/guidance_los/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
<?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>guidance_los</name>
<version>0.0.0</version>
<description>Package for implementing a LOS guidance action server.</description>
<maintainer email="[email protected]">badawi</maintainer>
<license>MIT</license>

<buildtool_depend>ament_cmake_python</buildtool_depend>

<depend>rclpy</depend>
<depend>std_msgs</depend>
<depend>nav_msgs</depend>
<depend>geometry_msgs</depend>
<depend>vortex_msgs</depend>
<depend>tf_transformations</depend>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>
Loading