-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Fixed topic names and initial tuning
- Loading branch information
Showing
6 changed files
with
99 additions
and
7 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
91 changes: 91 additions & 0 deletions
91
guidance/hybridpath_guidance/hybridpath_guidance/waypoint_node.py
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,91 @@ | ||
#!/usr/bin/env python3 | ||
|
||
import rclpy | ||
from rclpy.node import Node | ||
from vortex_msgs.srv import Waypoint | ||
from geometry_msgs.msg import Point | ||
from nav_msgs.msg import Odometry | ||
from transforms3d.euler import quat2euler | ||
import numpy as np | ||
|
||
class WaypointClient(Node): | ||
def __init__(self): | ||
super().__init__('waypoint_client') | ||
self.eta_odom = self.create_subscription(Odometry, '/seapath/odom/ned', self.eta_callback, 1) | ||
|
||
self.eta_received = False | ||
|
||
while not self.eta_received: | ||
self.get_logger().info('Waiting for eta...') | ||
rclpy.spin_once(self) | ||
|
||
self.client = self.create_client(Waypoint, 'waypoint_list') | ||
|
||
while not self.client.wait_for_service(timeout_sec=2.0): | ||
self.get_logger().info('service not available, waiting again...') | ||
|
||
self.send_request() | ||
|
||
def eta_callback(self, msg: Odometry): | ||
self.eta = self.odom_to_eta(msg) | ||
#self.get_logger().info(f'Received eta {self.eta}') | ||
self.eta_received = True | ||
|
||
def send_request(self): | ||
if self.eta_received: | ||
req = Waypoint.Request() | ||
wp_list = [[self.eta[0], self.eta[1]], [self.eta[0] + 3., self.eta[1]]] | ||
req.waypoint = [Point(x=float(wp[0]), y=float(wp[1]), z=0.0) for wp in wp_list] | ||
self.get_logger().info(f'Sending request: {req}') | ||
self.future = self.client.call_async(req) | ||
self.future.add_done_callback(self.get_response) | ||
|
||
def get_response(self, future): | ||
try: | ||
response = future.result() | ||
self.get_logger().info(f'Received response: {response}') | ||
if response.success: | ||
self.destroy_node() | ||
rclpy.shutdown() | ||
|
||
except Exception as e: | ||
self.get_logger().error('Service call failed %r' % (e,)) | ||
|
||
@staticmethod | ||
def odom_to_eta(msg: Odometry) -> np.ndarray: | ||
""" | ||
Converts an Odometry message to 3DOF eta vector. | ||
Args: | ||
msg (Odometry): The Odometry message to convert. | ||
Returns: | ||
np.ndarray: The eta vector. | ||
""" | ||
x = msg.pose.pose.position.x | ||
y = msg.pose.pose.position.y | ||
orientation_q = msg.pose.pose.orientation | ||
orientation_list = [ | ||
orientation_q.w, orientation_q.x, orientation_q.y, orientation_q.z | ||
] | ||
|
||
# Convert quaternion to Euler angles | ||
yaw = quat2euler(orientation_list)[2] | ||
|
||
state = np.array([x, y, yaw]) | ||
return state | ||
|
||
def main(args=None): | ||
rclpy.init(args=args) | ||
waypoint_client_node = WaypointClient() | ||
try: | ||
rclpy.spin(waypoint_client_node) | ||
except Exception as e: | ||
waypoint_client_node.get_logger().error(f'Unhandled exception: {e}') | ||
finally: | ||
if rclpy.ok(): | ||
waypoint_client_node.destroy_node() | ||
rclpy.shutdown() | ||
|
||
if __name__ == '__main__': | ||
main() |
4 changes: 2 additions & 2 deletions
4
motion/hybridpath_controller/config/hybridpath_controller_config.yaml
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,5 +1,5 @@ | ||
/**: | ||
ros__parameters: | ||
hybridpath_controller: | ||
K1_diag: [10.0, 10.0, 10.0] # First gain matrix | ||
K2_diag: [60.0, 60.0, 60.0] # Second gain matrix | ||
K1_diag: [1.0, 1.0, 1.0] # First gain matrix | ||
K2_diag: [40.0, 40.0, 40.0] # Second gain matrix |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters