Skip to content

Commit

Permalink
Moved K1 and K2 to yaml
Browse files Browse the repository at this point in the history
  • Loading branch information
Andeshog committed Mar 28, 2024
1 parent 76f9e45 commit 5f81a88
Show file tree
Hide file tree
Showing 4 changed files with 36 additions and 14 deletions.
2 changes: 2 additions & 0 deletions asv_setup/config/robots/freya.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,8 @@
buoyancy: 0 # kg
center_of_mass: [0, 0, 0] # mm (x,y,z)
center_of_buoyancy: [0, 0, 0] # mm (x,y,z)
inertia_matrix_diag: [] # kg
damping_matrix_diag: []


propulsion:
Expand Down
Original file line number Diff line number Diff line change
@@ -1 +1,5 @@
# K1 and K2 should be put here
/**:
ros_parameters:
gain_matrices:
K1_diag: [10, 10, 10] # First gain matrix
K2_diag: [60, 60, 60] # Second gain matrix
Original file line number Diff line number Diff line change
Expand Up @@ -4,18 +4,11 @@
from transforms3d.euler import quat2euler

class AdaptiveBackstep:
def __init__(self):
self.init_system()

def init_system(self) -> None:
self.K_1 = np.diag([10, 10, 10]) # First gain matrix
self.K_2 = np.diag([60, 60, 30]) # Second gain matrix
self.tau_max = np.array([41.0, 50.0, 55.0]) # Må tilpasses thrusterne

## Forenklet modell ## Bør også endres
m = 50
self.M = np.diag([m, m, m])
self.D = np.diag([10, 10, 5])
def __init__(self, K1: np.ndarray, K2: np.ndarray, M: np.ndarray, D: np.ndarray) -> None:
self.K_1 = K1
self.K_2 = K2
self.M = M
self.D = D

def control_law(self, state: Odometry, reference: HybridpathReference) -> np.ndarray:
"""
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
import rclpy
import numpy as np
from rclpy.node import Node
from hybridpath_controller.adaptive_backstep import AdaptiveBackstep
from geometry_msgs.msg import Wrench
Expand All @@ -8,12 +9,34 @@
class HybridPathControllerNode(Node):
def __init__(self):
super().__init__("hybridpath_controller_node")

self.declare_parameters(
namespace='',
parameters=[
("hybridpath_controller.K1_diag", [10, 10, 10]),
("hybridpath_controller.K2_diag", [60, 60, 60]),
("hybridpath_controller.M_diag", [50, 50, 50]),
("hybridpath_controller.D_diag", [10, 10, 5])
])

self.state_subscriber_ = self.state_subscriber_ = self.create_subscription(Odometry, "/sensor/seapath/odometry/ned", self.state_callback, 1)
self.hpref_subscriber_ = self.create_subscription(HybridpathReference, "guidance/hybridpath/reference", self.reference_callback, 1)
self.wrench_publisher_ = self.create_publisher(Wrench, "thrust/wrench_input", 1)

self.AB_controller_ = AdaptiveBackstep()
# Get parameters
K1_diag = self.get_parameter("hybridpath_controller.K1_diag").get_parameter_value().double_array_value
K2_diag = self.get_parameter("hybridpath_controller.K2_diag").get_parameter_value().double_array_value
M_diag = self.get_parameter("hybridpath_controller.M_diag").get_parameter_value().double_array_value
D_diag = self.get_parameter("hybridpath_controller.D_diag").get_parameter_value().double_array_value

# Transform parameters to diagonal matrices
K1 = np.diag(K1_diag)
K2 = np.diag(K2_diag)
M = np.diag(M_diag)
D = np.diag(D_diag)

# Create controller object
self.AB_controller_ = AdaptiveBackstep(K1, K2, M, D)

controller_period = 0.1
self.controller_timer_ = self.create_timer(controller_period, self.controller_callback)
Expand Down

0 comments on commit 5f81a88

Please sign in to comment.