Skip to content
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
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
7 changes: 7 additions & 0 deletions src/boat_simulator/boat_simulator/common/constants.py
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,9 @@
from enum import Enum
from typing import Dict

import numpy as np
from numpy.typing import NDArray


# Class declarations for constants. These are not meant to be accessed directly.
@dataclass
Expand Down Expand Up @@ -41,6 +44,8 @@ class BoatProperties:
sail_dist: float # Meters
rudder_dist: float # Meters
hull_drag_factor: float # Dimensionless
mass: float # Kilograms
inertia: NDArray[np.float64] # Kilogram meter squared


# Directly accessible constants
Expand Down Expand Up @@ -92,4 +97,6 @@ class BoatProperties:
sail_dist=5.0,
rudder_dist=1.5,
hull_drag_factor=0.05,
mass=200.0,
inertia=np.array([[10, 0, 0], [0, 30, 0], [0, 0, 20]], dtype=np.float32),
)
Original file line number Diff line number Diff line change
Expand Up @@ -110,8 +110,9 @@ def __init_private_attributes(self):
self.__rudder_angle = 0
self.__sail_trim_tab_angle = 0
self.__desired_heading = None
self._wind_sensor = WindSensor()
self.__boat_state = BoatState(
0.5, 1, np.array([[0.5, 0.5, 0.5], [0.0, 0.5, 0.5], [0.0, 0.0, 0.5]], dtype=np.float32)
0.5, Constants.BOAT_PROPERTIES.mass, Constants.BOAT_PROPERTIES.inertia
)
self.__wind_generator = FluidGenerator(
generator=MVGaussianGenerator(np.array([5, 5]), np.array([[2, 1], [1, 2]]))
Expand All @@ -120,6 +121,12 @@ def __init_private_attributes(self):
generator=MVGaussianGenerator(np.array([1, 1]), np.array([[2, 1], [1, 2]]))
)

def __update_wind_sensor(self):
"""Updates the wind sensor with the latest wind data from the wind generator."""
wind_data = self.__wind_generator.next()
self.__wind_sensor.speed.speed = wind_data[0]
Copy link
Contributor

Choose a reason for hiding this comment

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

I just happened to stumble upon this. You shouldn't have to assign the private members in this way. The update method is there to help you out, and you get additional functionality with noise/delays if you want. Try self.update(wind=wind_data[0])?

See the wind sensor tests for an example of this type of call.

self.__wind_sensor.direction = wind_data[1]
Copy link
Contributor

Choose a reason for hiding this comment

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

direction doesn't look like a field in the WindSensor class, you'll have to add it by following the pattern of other fields in these classes (ex: wind field)


def __declare_ros_parameters(self):
"""Declares ROS parameters from the global configuration file that will be used in this
node. This node will monitor for any changes to these parameters during execution and will
Expand Down Expand Up @@ -279,6 +286,7 @@ def __init_timer_callbacks(self):
# PUBLISHER CALLBACKS
def __publish(self):
"""Synchronously publishes data to all publishers at once."""
self.__update_wind_sensor()
self.__update_boat_state()
# TODO Get updated boat state and publish (should this be separate from publishing?)
# TODO Get wind sensor data and publish (should this be separate from publishing?)
Expand Down Expand Up @@ -307,16 +315,16 @@ def __publish_gps(self):
def __publish_wind_sensors(self):
"""Publishes mock wind sensor data."""
# TODO Update to publish real data
windSensor1 = WindSensor()
windSensor1.speed.speed = 0.0
windSensor1.direction = 0
# windSensor1 = WindSensor()
# windSensor1.speed.speed = 0.0
# windSensor1.direction = 0

windSensor2 = WindSensor()
windSensor2.speed.speed = 0.0
windSensor2.direction = 0
# windSensor2 = WindSensor()
# windSensor2.speed.speed = 0.0
# windSensor2.direction = 0

msg = WindSensors()
msg.wind_sensors = [windSensor1, windSensor2]
msg.wind_sensors = [self.__wind_sensor] * 2 # Accounts for two sensors with identical data

self.wind_sensors_pub.publish(msg)
self.get_logger().info(
Expand Down Expand Up @@ -562,7 +570,8 @@ def __update_boat_state(self):
sail_trim_tab_angle.
"""
self.__boat_state.step(
self.__wind_generator.next(),
self.__wind_sensor,
# self.__wind_generator.next(),
self.__current_generator.next(),
self.__rudder_angle,
self.__sail_trim_tab_angle,
Expand Down
Loading