Skip to content

Commit

Permalink
feat(#128): removed unneeded code
Browse files Browse the repository at this point in the history
  • Loading branch information
A1ice-Z authored and alekskl01 committed Jul 15, 2024
1 parent cbd3c19 commit e220ae5
Showing 1 changed file with 0 additions and 29 deletions.
29 changes: 0 additions & 29 deletions motion/colav/scripts/colav_controller.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,21 +10,12 @@
from transformations import euler_from_quaternion
from geometry_msgs.msg import Quaternion
import numpy as np

import matplotlib
matplotlib.use('Qt5Agg')
import matplotlib.pyplot as plt

plt.ion() # Turn interactive mode on
fig, ax = plt.subplots() # Pre-create the figure and axes

class ColavController(Node):

def __init__(self):
super().__init__("colav_controller")

self.vessel_path = [] # To store vessel positions over time

self.declare_parameter('guidance_interface/colav_data_topic', 'guidance/collision_avoidance')
self.declare_parameter('stop_zone_radius', 0.0)
self.declare_parameter('colimm_max_radius', math.inf)
Expand All @@ -50,9 +41,6 @@ def vessel_callback(self, msg):
self.vessel = self.odometry_to_obstacle(msg)
self.t = msg.header.stamp.sec + msg.header.stamp.nanosec / 1e9

self.vessel_path.append((self.vessel.x, self.vessel.y))
self.plot_positions()

def obst_callback(self, msg):
self.obstacles = [self.odometry_to_obstacle(odom) for odom in msg.odoms]
if not self.obstacles:
Expand Down Expand Up @@ -159,23 +147,6 @@ def get_zone(self, obstacle: Obstacle, vessel: Obstacle):
return Zones.COLIMM
return Zones.STOPNOW

def plot_positions(self):
ax.clear() # Clear previous drawings
if self.vessel_path:
path_x, path_y = zip(*self.vessel_path)
ax.plot(path_x, path_y, 'b-', label='Vessel Path')
ax.plot(self.vessel.x, self.vessel.y, 'bo', label='Vessel Current')
for obstacle in self.obstacles:
ax.plot(obstacle.x, obstacle.y, 'ro', label='Obstacle')
ax.set_xlabel('X position')
ax.set_ylabel('Y position')
ax.legend()
ax.grid(True)
plt.title('Vessel and Obstacles Position and Path')
fig.canvas.draw_idle() # Redraw the current figure
fig.canvas.flush_events() # Process events like key presses or resizes



def main(args=None):
rclpy.init()
Expand Down

0 comments on commit e220ae5

Please sign in to comment.