Skip to content

Commit

Permalink
Automated autoyapf fixes
Browse files Browse the repository at this point in the history
  • Loading branch information
github-actions committed Oct 9, 2024
1 parent 917d5bf commit cd4d076
Show file tree
Hide file tree
Showing 3 changed files with 39 additions and 17 deletions.
51 changes: 36 additions & 15 deletions guidance/guidance_pkg/guidance_pkg/guidance.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,30 +6,46 @@
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)
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)
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.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},
{
'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
Expand All @@ -47,7 +63,9 @@ def odom_callback(self, msg):

# 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]
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}

Expand All @@ -73,7 +91,7 @@ def timer_callback(self):
current_z = self.current_position.z

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

# Extract target waypoint position
Expand All @@ -82,15 +100,14 @@ def timer_callback(self):
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
)
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.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.')
Expand All @@ -115,7 +132,8 @@ def timer_callback(self):
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)
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)
Expand All @@ -133,18 +151,21 @@ def timer_callback(self):
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()
2 changes: 1 addition & 1 deletion guidance/guidance_pkg/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
packages=find_packages(exclude=['test']),
data_files=[
('share/ament_index/resource_index/packages',
['resource/' + package_name]),
['resource/' + package_name]),
('share/' + package_name, ['package.xml']),
],
install_requires=['setuptools'],
Expand Down
3 changes: 2 additions & 1 deletion guidance/guidance_pkg/test/test_copyright.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,8 @@


# 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.skip(
reason='No copyright header has been placed in the generated source file.')
@pytest.mark.copyright
@pytest.mark.linter
def test_copyright():
Expand Down

0 comments on commit cd4d076

Please sign in to comment.