Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Update wind sensor in physics engine node #444

Open
wants to merge 8 commits into
base: main
Choose a base branch
from
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@

import boat_simulator.common.constants as Constants
from boat_simulator.common.generators import MVGaussianGenerator
from boat_simulator.common.sensors import SimWindSensor
from boat_simulator.common.types import Scalar
from boat_simulator.nodes.physics_engine.fluid_generation import FluidGenerator
from boat_simulator.nodes.physics_engine.model import BoatState
Expand Down Expand Up @@ -182,6 +183,10 @@ def __init_private_attributes(self):
generator=MVGaussianGenerator(current_mean, current_cov)
)

# No delay in this instance
sim_wind = self.__wind_generator.next()
self.__sim_wind_sensor = SimWindSensor(sim_wind, enable_noise=True)

def __init_callback_groups(self):
"""Initializes the callback groups. Whether multithreading is enabled or not will affect
how callbacks are executed.
Expand Down Expand Up @@ -310,6 +315,7 @@ def __init_timer_callbacks(self):
# PUBLISHER CALLBACKS
def __publish(self):
"""Synchronously publishes data to all publishers at once."""
self.__update_sim_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 All @@ -318,6 +324,23 @@ def __publish(self):
self.__publish_kinematics()
self.__publish_counter += 1

def __update_sim_wind_sensor(self):
"""Updates wind parameter of wind sensor"""
self.__sim_wind_sensor.wind = self.__wind_generator.next()
kristatraboulay marked this conversation as resolved.
Show resolved Hide resolved

def __update_boat_state(self):
"""
Generates the next vectors for wind_generator and current_generator and updates the
boat_state with the new wind and current vectors along with the rudder_angle and
sail_trim_tab_angle.
"""
self.__boat_state.step(
self.__sim_wind_sensor.wind,
self.__current_generator.next(),
self.__rudder_angle,
self.__sail_trim_tab_angle,
)

def __publish_gps(self):
"""Publishes mock GPS data."""
# TODO Update to publish real data
Expand Down Expand Up @@ -586,19 +609,6 @@ def __sail_action_feedback_callback(
.double_value,
)

def __update_boat_state(self):
"""
Generates the next vectors for wind_generator and current_generator and updates the
boat_state with the new wind and current vectors along with the rudder_angle and
sail_trim_tab_angle.
"""
self.__boat_state.step(
self.__wind_generator.next(),
self.__current_generator.next(),
self.__rudder_angle,
self.__sail_trim_tab_angle,
)

# CLASS PROPERTY PUBLIC GETTERS
@property
def is_multithreading_enabled(self) -> bool:
Expand Down
Loading