munetauvsim.vehicles

Vehicle classes for AUV simulation with swarm coordination.

Implements abstract and concrete vehicle classes for autonomous underwater vehicle simulation, including 6-DOF dynamics, modular GNC architecture, sensor integration, and multi-agent communication capabilities.

Classes

Vehicle

Abstract base class for vehicle hierarchy.

AUV

Abstract AUV class with sensor management and GNC interfaces.

Remus100s

Concrete Remus 100 AUV implementation with full dynamics.

Model

Lightweight vehicle state model for swarm coordination.

Functions

buildGroup(num, gid, hasLeader, vehType, kwargs)

Create a list of vehicle instances for multi-agent simulation.

Notes

Based on Fossen’s marine vehicle dynamics formulation and Python Vehicle Simulator.

References

[1] Fossen, T.I. Python Vehicle Simulator. GitHub repository. https://github.com/cybergalactic/PythonVehicleSimulator

[2] Fossen, T.I. (2021). Handbook of Marine Craft Hydrodynamics and Motion Control. 2nd Edition, Wiley. https://www.fossen.biz/wiley

Functions

abstractmethod(funcobj)

A decorator indicating abstract methods.

buildGroup(num, gid[, hasLeader, vehType])

Create a list of vehicle instances for swarm simulation.

Classes

ABC()

Helper class that provides a standard way to create an ABC using inheritance.

AUV()

Abstract base class for autonomous underwater vehicles.

Model(vehObj)

Lightweight data model representing another vehicle's state in multi-agent simulations.

NDArray

alias of ndarray[Any, dtype[ScalarType]]

NPFltArr

alias of ndarray[Any, dtype[float64]]

Remus100s(**kwargs)

Remus 100 cylinder-shaped AUV model for multi-agent swarm simulation research.

Vehicle()

Abstract base class for structural hierarchy of vehicle classes.

class munetauvsim.vehicles.Vehicle[source]

Bases: ABC

Abstract base class for structural hierarchy of vehicle classes.

abstract __init__()[source]

Define and set vehicle attributes.

Return type:

None

class munetauvsim.vehicles.Model(vehObj)[source]

Bases: Vehicle

Lightweight data model representing another vehicle’s state in multi-agent simulations.

The Model class stores data about another vehicle for use in swarm coordination where vehicles maintain internal models of their neighbors’ states based on received communication messages. Includes historical logging of position and velocity reports with automatic capacity expansion.

Parameters:

vehObj (Vehicle) – The source vehicle to create a model from. Copies the following attributes into the model: callSign, id, groupId, isLeader, eta, velocity, nextEta, nextVel.

Attributes

Identity and Status:

callsignstr

Vehicle’s unique identifier

idint

Vehicle ID number

groupIdstr

Swarm group identifier

isLeaderbool

True if vehicle is a group leader

State Vectors:

etandarray, shape (3,)

Vehicle position [x,y,z] in END frame (m)

velocityndarray, shape (3,)

Vehicle velocity [vx, vy, vz] in END frame (m/s)

nextEtandarray

Projected next position (if available)

nextVelndarray

Projected next velocity (if available)

Communication:

nodeAddrint

Simulation comms address.

timeLastMsgfloat

Timestamp the last received message was sent from this vehicle (s)

delayLastMsgfloat

Time elapsed since last received message (s)

rprtRecvbool

Flag indicating last report successfully received

Data Logs:

etaLogndarray, shape (logCap, 4)

Log of received position reports, [x, y, z, time]

velLogndarray, shape (logCap, 5)

Log of received velocity reports, [vx, vy, vz, speed, time]

logSizeint

Current number of filled log entries, (0 to logCap)

logCapint

Current capacity of preallocated log arrays, starts at 512 and doubles when full

Notes

  • Uses __slots__ to minimize memory overhead. New attributes cannot be dynamically added, they must be defined in the class and added to the __slots__ declaration.

  • When logs reach capacity, both are automatically doubled in size by the communication.writeEtaVelLogs() function.

__init__(vehObj)[source]

Create vehicle model from existing vehicle object.

Parameters:

vehObj (Vehicle) – Source vehicle to copy attributes from (callSign, id, groupId, nodeAddr, isLeader, eta, velocity, nextEta, nextVel).

Return type:

None

Notes

Initializes communication tracking (timeLastMsg, delayLastMsg) and preallocates log arrays with 512-row capacity.

callSign
id
groupId
nodeAddr
isLeader
eta
velocity
nextEta
nextVel
timeLastMsg
delayLastMsg
etaLog
velLog
rprtRecv
__repr__()[source]

Return concise string representation of Model object.

Return type:

str

class munetauvsim.vehicles.AUV[source]

Bases: Vehicle

Abstract base class for autonomous underwater vehicles.

Provides sensor management, GNC interfaces, and common vehicle attributes. Cannot be instantiated directly; must be subclassed by concrete vehicle types.

Attributes

idint

Unique vehicle identifier.

groupIdstr

Swarm group identifier.

isLeaderbool

Leadership status in swarm.

callSignstr

Custom unique vehicle identifier.

etandarray, shape (6,)

Position and attitude [x, y, z, phi, theta, psi].

nundarray, shape (6,)

Body-frame velocities [u, v, w, p, q, r].

sensorsdict

Installed sensor objects keyed by name.

GuidSystemcallable

Guidance system function (assigned via load methods).

CommNetworkobject

Communication network manager.

Methods

addSensor(name, sensor)

Install a sensor on the vehicle.

readSensor(name, kwargs)

Read data from a specific sensor.

collectSensorData(i, ocean)

Update vehicle state from sensors (abstract method).

abstract __init__()[source]

Initialize base AUV attributes.

Sets up identity attributes, state vectors, sensor dictionary, and GNC function handle placeholders. All assigned method attributes (GuidSystem, CommNetwork, etc.) are initialized to None.

Notes

This is an abstract class constructor called by subclass __init__. Concrete vehicles (e.g., Remus100s) must call super().__init__().

Return type:

None

z_safe

x, y, z, roll, pitch, yaw nu=[u,v,w,p,q,r]: linear & angular velocities: BODY frame velocity=[x_dot,y_dot,z_dot] linear velocities: NED frame

Type:

eta=[e,n,d,phi,theta,psi]

wn_d_z

wn_d_z also gets recalculated by the @sampleTime.setter

property id: int

Unique vehicle ID number

property groupId: str

The vehicle group ID

property isLeader: bool

The vehicle Leader status

property callSign: str

Unique vehicle identifier

property sampleTime: float

0.02

Type:

The iteration loop time step (seconds), default

property Delta

Positive look-ahead distance used by ALOS (m), typically 5-20 m

property target: Model | Vehicle | None

The vehicle target for tracking

property CommNetwork: AquaNetManager | MuNode | None

The Communication Network Manager

property fullDetails: str

The full details of the all the AUV attributes

property immobilized: bool

Mobility status of AUV

__repr__()[source]

Return concise string representation of AUV object.

Return type:

str

__str__()[source]

Return user-friendly string representation with vehicle info.

Return type:

str

syncEnvironmentState(i, ocean)[source]

Inject true environmental state for the current simulation step.

Called by the Simulator each iteration to inject true environmental conditions directly into the vehicle for dynamics calculations. These values represent the physical reality of the environment and are used exclusively by the vehicle dynamics method for accurate force and collision computations.

Parameters:
  • i (int) – Current simulation iteration counter. Used to index time-varying environmental arrays (e.g., current speed and direction).

  • ocean (env.Ocean) –

    Ocean environment object containing:

    • currentenv.Current1D or None

      Time-varying current model with speed and angle arrays.

    • floorenv.Floor or None

      Bathymetric floor model with callable floor(x, y).

Return type:

None

Notes

Side Effects:

Updates the following vehicle attributes:

  • V_cfloat

    True ocean current speed (m/s).

  • beta_V_cfloat

    True ocean current direction (rad).

  • z_floorfloat

    True ocean floor depth at vehicle position (m).

These attributes feed directly into dynamics() and are not intended for use by guidance or navigation algorithms. For sensed estimates of environmental conditions, see collectSensorData().

Separation from Sensor Pathway:

This method and collectSensorData() represent two distinct pathways for environmental data on the vehicle:

  • syncEnvironmentState() – true environment state injection from the simulator (e.g z_floor, V_c, beta_V_c) for vehicle dynamics calculations.

  • collectSensorData() – sensor-based observations (e.g. seabed_z, drift_c, set_c) for use by guidance and navigation algorithms or environmental data collection.

See also

collectSensorData

Sensor-based environmental observation pathway.

dynamics

Utilizes V_c, beta_V_c, z_floor for physics evaluations.

addSensor(name, sensor)[source]

Install or replace a sensor in the vehicle’s sensor suite.

Adds a sensor object to the vehicles internal sensor dictionary, making it available for data collection during simulation. If a sensor with the specified name already exists, it is replaced. The vehicle’s info dictionary is automatically updated to reflect the current sensor configuration.

Parameters:
  • name (str) –

    Unique identifier for the sensor. This name is used as the dictionary key and for subsequent sensor operations (read, remove). Names are case-sensitive and should be descriptive.

    Common conventions:

    • ’current’: Ocean currentr sensor

    • ’depth’: Ocean floor depth sensor

  • sensor (nav.Sensor) – Sensor object to install on the vehicle. The sensor’s collectData method will be called during simulation with relevant parameters (ocean, eta, etc.) passed as keyword arguments.

Return type:

None

Notes

Side Effects:

  • Calls _updateSensorInfo() to update self.info[‘Installed Sensors’]

Sensor Interface Requirements:

All sensors must inherit from nav.Sensor and implement collectData() method with the signature:

def collectData(self, **kwargs)->Any

The collectData method should:

  • Extract only needed parameters from kwargs

  • Return sensor measurement(s) in appropriate format

  • Handle missing parameters gracefully (return None or raise ValueError)

Data Collection Timing:

Sensors are automatically read during simulation via the vehicle’s collectSensorData() method, which is called once per simulation iteration. The simulator provides ocean state and other context via kwargs.

Sensor Data Flow:

  1. Simulation calls vehicle.collectSensorData(i, ocean)

  2. Vehicle calls vehicle.readAllSensors() or readSensor(name)

  3. Sensor.collectData() extracts parameters and returns measurement

  4. Vehicle updates internal state (e.g., seabed_z, etc.)

See also

addSensors

Add multiple sensors at once from dictionary

removeSensor

Remove sensor by name

removeSelectedSensors

Remove multiple sensors by name list

removeAllSensors

Remove all sensors at once

readSensor

Read data from specific sensor

readSelectedSensors

Read multiple sensors by name list

readAllSensors

Read data from all installed sensors

collectSensorData

Main sensor data collection method called by

simulator

updateSensorInfo

Helper that updates info dictionary

Examples

### Install default ocean sensors:

>>> auv = Remus100s()
>>> auv.addSensor('current', nav.OceanCurrentSensor())
>>> auv.addSensor('depth', nav.OceanDepthSensor())
>>> print(auv.info['Installed Sensors'])
current, depth

### Install a custom depth sensor:

>>> class CustomDepthSensor(nav.Sensor):
...     def collectData(self, **kwargs):
...         ocean = kwargs.get('ocean')
...         eta = kwargs.get('eta')
...         # custom sensor logic
...         return customData
>>> auv.addSensor('depth', CustomDepthSensor())

### Read sensor during simulation:

>>> speed, angle = auv.readSensor('current', ocean, i)
>>> print(f"Current: {speed:.2f} m/s at {np.degrees(angle):.1f} deg")
addSensors(sensors)[source]

Install or replace multiple sensors on the vehicle simultaneously.

Batch operation for adding several sensors at once from a dictionary. The vehicle’s info dictionary is updated once after all sensors are processed.

Parameters:

sensors (dict {str : nav.Sensor}) – Dictionary mapping sensor names to sensor objects. Keys are unique identifier strings (same conventions as addSensor), values must be nav.Sensor instances.

Return type:

None

Notes

Side Effects:

  • Calls _updateSensorInfo() to update self.info[‘Installed Sensors’]

  • Invalid entries (not a nav.Sensor instance) are reported and skipped

Validation:

Each sensor value is checked for being an instance of nav.Sensor. Invalid objects generate an error log message and are not installed. This allows partial installation of valid sensors even if some entries are invalid.

See also

addSensor

Add single sensor

removeSensor

Remove sensor by name

removeSelectedSensors

Remove multiple sensors by name list

removeAllSensors

Remove all sensors at once

readSensor

Read data from specific sensor

readSelectedSensors

Read multiple sensors by name list

readAllSensors

Read data from all installed sensors

collectSensorData

Main sensor data collection method called by

simulator

updateSensorInfo

Helper that updates info dictionary

Examples

### Install complete sensor kit all at once:

>>> auv = Remus100s()
>>> sensors = {
...     'current': nav.OceanCurrentSensor(),
...     'depth': nav.OceanCurrentSensor(),
...     'custom': someCustomSensor(),
... }
>>> auv.addSensors(sensors)
>>> print(auv.info['Installed Sensors'])
current, depth, custom
removeSensor(name)[source]

Remove a sensor from the vehicle’s sensor suite by name.

Deletes the specified sensor from the vehicle’s internal sensor dictionary and updates the info display.

Parameters:

name (str) – Unique identifier of the sensor to remove. Must match a key in the self.sensors dictionary exactly (case-sensitive).

Return type:

None

Notes

Side Effects:

  • Calls _updateSensorInfo() to update self.info[‘Installed Sensors’]

Safe Operation:

Attempting to remove a non-existent sensor does not raise an exception. Instead, a warning is reported and operation continues. This allows safely calling removeSensor without checking existence first.

See also

addSensor

Add single sensor

addSensors

Add multiple sensors at once from dictionary

removeSelectedSensors

Remove multiple sensors by name list

removeAllSensors

Remove all sensors at once

readSensor

Read data from specific sensor

readSelectedSensors

Read multiple sensors by name list

readAllSensors

Read data from all installed sensors

collectSensorData

Main sensor data collection method called by

simulator

updateSensorInfo

Helper that updates info dictionary

Examples

### Remove a single sensor:

>>> auv = Remus100s()
>>> auv.addSensor('current', nav.OceanCurrentSensor())
>>> auv.addSensor('depth', nav.OceanDepthSensor())
>>> print(auv.info['Installed Sensors'])
current, depth
>>> auv.removeSensor('current')
>>> print(auv.info['Installed Sensors'])
depth
removeSelectedSensors(names)[source]

Remove multiple sensors from the vehicle by providing a list of names.

Batch removal operation that processes a list of sensor names. The vehicle’s info dictionary is updated once after all sensors are processed.

Parameters:

names (list of str) – List of sensor identifier strings to remove. Each string should match a key in self.sensors dictionary (case-sensitive).

Return type:

None

Notes

Side Effects:

  • Calls _updateSensorInfo() to update self.info[‘Installed Sensors’]

Partial Removal:

If some sensor names in the list don’t exist they are reported and skipped, while valid names are still removed.

See also

addSensor

Add single sensor

addSensors

Add multiple sensors at once from dictionary

removeSensor

Remove sensor by name

removeAllSensors

Remove all sensors at once

readSensor

Read data from specific sensor

readSelectedSensors

Read multiple sensors by name list

readAllSensors

Read data from all installed sensors

collectSensorData

Main sensor data collection method called by

simulator

updateSensorInfo

Helper that updates info dictionary

Examples

### Remove multiple sensors at once:

>>> auv = Remus100s()
>>> auv.addSensors({
...     'current': nav.OceanCurrentSensor(),
...     'depth': nav.OceanDepthSensor(),
...     'custom': someCustomSensor(),
... })
>>> auv.removeSelectedSensors(['current', 'custom'])
>>> print(auv.info['Installed Sensors'])
depth
removeAllSensors()[source]

Remove all installed sensors from the vehicle’s sensor suite.

Clears the entire sensor dictionary and updates the info display.

Notes

Calls _updateSensorInfo() to remove sensor list from self.info

See also

addSensor

Add single sensor

addSensors

Add multiple sensors at once from dictionary

removeSensor

Remove sensor by name

removeSelectedSensors

Remove multiple sensors by name list

readSensor

Read data from specific sensor

readSelectedSensors

Read multiple sensors by name list

readAllSensors

Read data from all installed sensors

collectSensorData

Main sensor data collection method called by

simulator

updateSensorInfo

Helper that updates info dictionary

Examples

### Reconfigure sensor suite:

>>> auv.removeAllSensors()
>>> auv.addSensors({
...     'custom_current': CustomCurrentSensor(),
...     'custom_depth': CustomDepthSensor(),
... })
Return type:

None

readSensor(name, *args, **kwargs)[source]

Read data from a single sensor by name with provided parameters.

Calls the collectData method of the specified sensor, passing along any provided arguments. Returns the sensor’s data output or None if the sensor is not found or if data collection fails.

Parameters:
  • name (str) – Unique identifier of the sensor to read from. Must match a key in self.sensors dictionary exactly (case-sensitive).

  • *args (tuple, optional) – Positional arguments to pass to the sesnor’s collectData method. Since this reads a single known sensor, positional arguments are supported for convenience.

  • **kwargs (dict, optional) –

    Keyword arguments to pass to the sensor’s collectData method. The sensor extracts only the parameters it needs.

    Common kwargs include:

    • oceanenv.Ocean

      Ocean environment object for current and depth data

    • etandarray

      Vehicle position for location-dependent sensing

    • iint

      Simulation iteration counter for time-dependent sensing

Returns:

data (Any or None) – Sensor data defined by the sensor’s collectData method.

Common return types:

  • tuple : (value1, value2, …) for multi-valued sensors

  • float : Single scalar measurement

  • ndarray : Vector or array measurement

  • None : Sensor not found or data collection failed

Return type:

Any | None

Notes

Side Effects:

Calls sensor.collectData() for named sensor

Argument Passing:

Supports positional arguments (*args) for convenience since the method only calls a single sensor.

Error Handling:

Returns None and reports issue if a sensor is not found or there is an error during data collection, allowing the simulation to continue.

Return Type Variability:

Return type depends on specific sensor implementation. Check sensor documentation for expected return format.

See also

addSensor

Add single sensor

addSensors

Add multiple sensors at once from dictionary

removeSensor

Remove sensor by name

removeSelectedSensors

Remove multiple sensors by name list

removeAllSensors

Remove all sensors at

readSelectedSensors

Read multiple sensors by name list

readAllSensors

Read data from all installed sensors

collectSensorData

Main sensor data collection method called by

simulator

updateSensorInfo

Helper that updates info dictionary

Examples

### Read ocean current sensor with keyword arguments

>>> auv = Remus100s()
>>> ocean = env.Ocean(spd=0.5, ang=np.pi/4)
>>> speed, angle = auv.readSensor('current', ocean=ocean, i=100)
>>> print(f"Current: {speed:.2f} m/s at {np.degrees(angle):.1f} deg")
Current: 0.50 m/s at 45.0 deg

### Read ocean depth sensor with positional arguments

>>> depth = auv.readSensor('depth', ocean, auv.eta)
>>> print(f"Ocean floor at {depth:.1f} m")
Ocean floor at 132.9 m
readSelectedSensors(names, **kwargs)[source]

Read data from multiple sensors by providing a list of sensor names.

Batch operation that reads several sensors at once, collecting their data into a dictionary. Keyword arguments are passed to all sensors, with each sensor extracting only the parameters it needs. Missing sensors are logged as errors.

Parameters:
  • names (list of str) – List of sensor identifier strings to read from. Each string should match a key in self.sensors dictionary. Names are case-sensitive.

  • **kwargs (dict) –

    Keyword arguments passed to each sensor’s collectData method. All sensors receive the same kwargs dictionary but extract only needed parameters.

    Common kwargs:

    • oceanenv.Ocean

      Ocean environment object for current and depth data

    • etandarray

      Vehicle position for location-dependent sensing

    • iint

      Simulation iteration counter for time-dependent sensing

Returns:

data (dict of {str : Any}) – Dictionary mapping sensor names to their collected data. Keys are sensor names from the input list (only for successfully read sensors). Values are dependent on what each sensor’s collectData method returns. Sensors that are not found are omitted from the returned dictionary.

Return type:

Dict[str, Any]

Notes

Side Effects:

Calls collectData() on each sensor

Keyword Argument Sharing:

All sensors receive the same kwargs dictionary. Each sensor must be careful to extract only what it needs via kwargs.get() and not unintentionally modify shared kwargs.

Partial Success:

If some sensors in the list do not exist, data is still collected from valid sensors. The returned dictionary contains only successfully read sensor entries.

No Positional Arguments:

Unlike readSensor(), this method calls multiple sensors so does not support positional arguments because there are no requirements that each sensor takes the same set of arguments or takes them in the same order.

See also

addSensor

Add single sensor

addSensors

Add multiple sensors at once from dictionary

removeSensor

Remove sensor by name

removeSelectedSensors

Remove multiple sensors by name list

removeAllSensors

Remove all sensors at

readSensor

Read data from specific sensor

readAllSensors

Read data from all installed sensors

collectSensorData

Main sensor data collection method called by

simulator

updateSensorInfo

Helper that updates info dictionary

Examples

### Read multiple sensors

>>> auv.Remus100s()
>>> ocean = env.Ocean(spd=0.5, ang=np.pi/4)
>>> data = auv.readSelectedSensors(
...     ['current','depth'],
...     ocean=ocean, eta=auv.eta, i=100,
... )
>>> print(f"Ocean Current Speed: {data['current'][0]:.2f} m/s")
Ocean Current Speed: 0.50 m/s
readAllSensors(**kwargs)[source]

Read data from all installed sensors simultaneously.

Batch operation that collects data from every installed sensor in the vehicle’s sensor suite, returning a dictionary mapping sensor names to their data outputs. Keyword arguments are passed to all sensors, with each extracting only the parameters it needs.

Parameters:

**kwargs (dict) –

Keyword arguments passed to each sensor’s collectData method. All sensors receive the same kwargs dictionary.

Common kwargs:

  • iint

    Simulation iteration counter for time-dependent sensing

  • oceanenv.Ocean

    Ocean environment object for current and depth data

  • etandarray

    Vehicle position for location-dependent sensing

Returns:

data (dict of {str : Any}) – Dictionary mapping sensor names to their collected data. Keys are sensor names from the input list. Values are dependent on what each sensor’s collectData method returns. If no sensors are installed, returns empty dictionary {}.

Return type:

Dict[str, Any]

Notes

Side Effects:

Calls collectData on each installed sensor

Use in Simulation:

This method is typically called by collectSensorData(), which is called once per simulation iteration by the Simulator.

Error Handling:

Individual sensor errors are not caught here. Method assumes each sensor is responsible for handling own exceptions, otherwise it propagates them up. If more robust error handling is needed, use readSelectedSensors or readSensor which catch errors.

See also

addSensor

Add single sensor

addSensors

Add multiple sensors at once from dictionary

removeSensor

Remove sensor by name

removeSelectedSensors

Remove multiple sensors by name list

removeAllSensors

Remove all sensors at

readSensor

Read data from specific sensor

readSelectedSensors

Read multiple sensors by name list

collectSensorData

Main sensor data collection method called by simulator

updateSensorInfo

Helper that updates info dictionary

Examples

### Read all sensors

>>> auv.Remus100s()
>>> ocean = env.Ocean(spd=0.5, ang=np.pi/4)
>>> data = auv.readAllSensors(ocean=ocean, eta=auv.eta, i=100)
>>> for sensor,value in data.items():
...     print(f"{sensor}: {value}")
current: [0.50, 0.79]
depth: 132.9
abstract collectSensorData()[source]

Collect data from installed sensors and update the vehicle state.

Notes

This method should be implemented by each vehicle class to collect data from and update the vehicle state accordingly.

Return type:

None

_updateSensorInfo()[source]

Update sensor information in the vehicle info dictionary.

Return type:

None

class munetauvsim.vehicles.Remus100s(**kwargs)[source]

Bases: AUV

Remus 100 cylinder-shaped AUV model for multi-agent swarm simulation research.

This class provides a physically-based Remus 100 model with complete 6-DOF nonlinear dynamics, customized to support full swarm operation, modular GNC architecture, networking communication, swarm coordination capabilities, and sensor integration.

Parameters:

**kwargs (dict, optional) –

Keyword arguments for vehicle customization. Common options include:

groupIdstr

Swarm group identifier, single character (e.g., “A”)

isLeaderbool

True if vehicle is a swarm group leader

callSignstr

Custom vehicle identification string

Any vehicle attribute can be overridden via kwargs.

Attributes

State Vectors:

etandarray, shape (6,)

Position and attitude [x, y, z, roll, pitch, yaw]

nundarray, shape (6,)

Body-frame velocities [u, v, w, p, q, r]

velocityndarray, shape (3,)

END-frame linear velocities [x_dot, y_dot, z_dot]

u_actualndarray, shape (3,)

Actual control inputs [rudder, stern, propeller]

Control Gains (PID Controllers):

Kp_z, Ki_zfloat

Depth control proportional and integral gains

Kp_theta, Ki_theta, Kd_thetafloat

Pitch control PID gains

Kp_psi, Ki_psi, Kd_psifloat

Heading control PID gains

K_ffloat

Observer gain for desired yaw angle

Swarm Coordination:

targetVehicle or Model

Target vehicle for tracking

grouplist of Vehicle or Model

List of swarm group member vehicles

r_safefloat

Minimum safe vehicle separation distance, 10.0 m

r_avoidfloat

Avoidance radius for APF repulsion, 40.0 m

r_innerfloat

Inner radius of neutral APF around following distance, 80.0 m

r_followfloat

Preferred following distance, 100.0 m

Waypoint Navigation:

wptguidance.Waypoint

Waypoint database for path following

wpt_kint

Index to previous active waypoint

R_switchfloat

Waypoint acceptance radius, 10.0 m

Deltafloat

Look-ahead distance for ALOS, 10.0 m

gammafloat

Adaptive gain constant for ALOS, 0.0006

Assigned Methods (Function Handles)

These attributes are designed to hold function references that are assigned via a custom load* method or manual assignment, enabling modular GNC architecture:

CommNetworkobject

Communication network manager (AquaNet or MuNet)

CommSchedcallable

Communication scheduling function

GuidSystemcallable

Main guidance coordinator that integrates components of the guidance system at a high-level. Orchestrates observers and autopilots to generate control commands based on specified guidance law.

GuidLawcallable

Core guidance algorithm implementing specific mathematical approaches for path generation. Returns either desired heading angles (e.g., ALOS) or velocity vectors (e.g. APF) based on current state and mission objectives.

DepthObscallable

Depth command filter and state estimator. Processes desired depth through smoothing algorithm to generate feasible depth command while respecting vehicle and environmental constraints.

HeadingObscallable

Heading state estimator and reference generator. Filters guidance-generated heading commands and estimates desired yaw rates.

Attitudecallable

Attitude propagation function (default: attitudeEuler)

DepthAPcallable

Depth autopilot implementing the control architecture, such as PI/PID, for pitch or stern plane deflection commands.

HeadingAPcallable

Heading autopilot implementing the control arichitecture, such as PI/PID, for rudder deflection commands.

PropCmdcallable

Propeller command generator for thrust management. Converts speed requirements to RPM commands, supporting both constant thrust profiles and dynamic speed control based on guidance demands

Methods

dynamics(u_control):

Integrate 6-DOF equations of motion using Euler’s method.

xferN2U(rpm):

Convert propeller RPM to vehicle speed (m/s).

xferU2N(speed):

Convert vehicle speed (m/s) to propeller RPM.

collectSensorData(i, ocean)

Read and update environmental sensor data.

loadPathFollowing():

Assign GNC for path following guidance system. Default is ALOS.

loadTargetTracking(target, law, att, rep)

Assign GNC for target tracking guidance system. Default is APF.

loadConstantProp(n_setpt):

Set constant propeller RPM command

loadAquaNetTdmaLF(epDur, bcDur, rpDur):

Configure TDMA communication via AquaNet for leader-follower systems.

loadMuNetLF(network, kwargs)

Configure communication via MuNet with FDMA or TDMA access modes.

Notes

Remus 100 Physical Properties:

Controlled by a tail rudder, stern planes, and a propeller.

  • Length: 1.6 m

  • Diameter: 19 cm

  • Mass: 31.9 kg

  • Max Speed: 2.5 m/s @ 1525 rpm

  • Max Fin Angle: 30 deg

  • Max Depth: 100 m

Vehicle Model:

This implementation follows the physical and hydrodynamic parameters from the Remus 100 AUV specifications. The dynamics model includes:

  • Rigid body and added mass effects

  • Coriolis and centripetal forces

  • Linear and quadratic damping

  • Propeller thrust

  • Control surface lift and drag forces

  • Environmental coupling (ocean currents, depth limits)

  • Actuator dynamics with first-order time constants

  • Saturation limits on all control surfaces

The modular GNC architecture allows arbitrary function assignment to the Assigned Methods attributes, enabling flexible experimentation with different guidance, navigation, and control algorithms.

References

[1] Fossen, T.I. Python Vehicle Simulator. GitHub repository. https://github.com/cybergalactic/PythonVehicleSimulator

[2] Fossen, T.I. (2021). Handbook of Marine Craft Hydrodynamics and Motion Control. 2nd Edition, Wiley. ISBN: 978-1-119-57505-4

Examples

### Create a basic AUV:

>>> auv = Remus100s()
>>> print(f"Max speed: {auv.u_max} m/s, Max depth: {auv.z_max} m")
Max speed: 2.5 m/s, Max depth: 100 m

### Assign custom function to guidance system:

>>> def custom_guidance(vehicle):
...     # ... Custom guidance logic ...
...     return np.array([rudder, stern, prop])
>>> auv.GuidSystem = custom_guidance
>>> delta_r, delta_s, n = auv.GuidSystem(auv)

### Create swarm leader with waypoint path following:

>>> leader = Remus100s(groupId="X", isLeader=True)
>>> leader.wpt = guid.Waypoint([0, 100, 200], [0, 100, 0], [10, 20, 30])
>>> leader.loadPathFollowing()
>>> leader.loadConstantProp(n_setpt=1200)

### Create swarm follower with APF target tracking:

>>> follower = Remus100s(groupId="X")
>>> follower.loadTargetTracking(leader, law="APF", att="linearCBZ",
...     rep="varExp")
>>> print(follower)
AUV 03 - Group X
----------------
Guidance System: Target Tracking, APF
Target: X02-LEADER
__init__(**kwargs)[source]

Initialize Remus100s AUV with complete state, physics, and swarm parameters.

Sets up all vehicle attributes including physical properties, hydrodynamic coefficients, control system gains, sensor suite, navigation parameters, swarm coordination settings, and communication interfaces. All systems are initialized to safe default values based on the Remus 100 specifications.

Parameters:

**kwargs (dict, optional) –

Arbitrary keyword arguments to override default attributes. Any attribute defined in the class can be set via kwargs. Common customizations:

  • groupIdstr

    Swarm group identifier, single character (e.g., “A”)

  • isLeaderbool

    Set True to designate as group leader (default: False)

  • callSignstr

    Custom vehicle identifier for display and logging (default: id+groupId)

Any other vehicle attribute can be overridden, but use caution: modifying physical parameters affects dynamics accuracy.

Return type:

None

Notes

Attributes Initialized:

The __init__ method initializes the following attribute categories:

  • Identity & Classification:

    • Increments class instance count variable num

    • Inherits from parent AUV class

    • Sets modelName, modelType, controls description

    • Assigns unique id based on class instance count

  • Physical & Hydrodynamic Properties:

    • Dimensions: L (length), diam (diameter)

    • Mass properties: rigid body mass, moments of inertia

    • Hydrodynamic coefficients: added mass, damping, drag

    • Propeller: thrust/torque coefficients (Wageningen B-series)

    • Control surfaces: rudder and stern plane parameters

    • See Fossen (2021) Section 8.4.2 for derivations

  • Control System Gains:

    • Depth control: Kp_z, Ki_z (outer PI loop)

    • Pitch control: Kp_theta, Ki_theta, Kd_theta (inner PID loop)

    • Heading control: Kp_psi, Ki_psi, Kd_psi (PID)

    • Observer gains: K_f for heading estimation

    • Propeller: n_setpt, n_rate for thrust management

  • State Vectors:

    • eta: position/attitude [x, y, z, phi, theta, psi]

    • nu: body velocities [u, v, w, p, q, r]

    • velocity: END velocities [x_dot, y_dot, z_dot]

    • u_actual: control inputs [rudder, stern, propeller]

  • Sensor Suite:

    • OceanDepthSensor: measures ocean floor depth

    • Additional sensors can be added via addSensor() method

  • Navigation Parameters:

    • z_max: maximum operating depth (100 m)

    • z_safe: safety distance from sensed ocean floor (5 m)

    • wn_d_z: desired natural frequency for depth (1/s)

  • Swarm Coordination:

    • r_safe: minimum safe separation (10 m)

    • r_avoid: avoidance radius for APF (40 m)

    • r_inner: inner radius of neutral follow zone (80 m)

    • r_follow: preferred following distance (100 m)

    • target: reference to leader vehicle (initially None)

    • group: list of swarm neighbors, excludes self (initially None)

  • Waypoint Navigation:

    • wpt: waypoint database (initialized empty at origin)

    • wpt_k: active waypoint index (0)

    • R_switch: waypoint acceptance radius (10 m)

    • Delta: look-ahead distance for ALOS (10 m)

    • gamma: adaptive gain for ALOS (0.0006)

    • betachat: crab angle estimate (0)

  • Communication:

    • All communication attributes initially None

    • Configured via custom loading methods (e.g. loadMuNetLF())

  • GNC Function Handles:

    • All assigned method attributes initially None

    • Configured via custom loading methods (e.g. loadPathFollowing())

Side Effects:

  • Increments Remus100s.num class variable

  • Calls parent AUV.__init__() to set up inherited attributes

  • Installs default sensors (current and depth)

  • Updates vehicle info dictionary with model details

Initialization Order:

  1. Update class instance counter

  2. Call parent class __init__

  3. Set identity and model information

  4. Initialize navigation parameters and sensors

  5. Initialize control state vector (u_actual)

  6. Set control gains and propeller parameters

  7. Initialize physics and hydrodynamics (comprehensive)

  8. Apply user-specified kwargs overrides

Default Configuration:

The vehicle is initialized in a neutral, safe state:

  • Position at origin (0, 0, 0)

  • Zero velocity and angular rates

  • No active guidance, navigation, or control systems

  • Default sensor suite installed

  • Ready for configuration via manual assignment or custom loading methods

Kwargs Override Behavior:

Any attribute can be overridden via kwargs, but this occurs AFTER all default initialization, so computed attributes (like mass matrix) are not automatically recalculated if you override component parameters. For major physics changes, consider subclassing rather than using kwargs.

T_n

(Fossen 2021, Section 8.4.2)

r_bb

CD_0, i.e. zero lift and alpha = 0 F_drag = 0.5 * rho * Cd * (pi * b^2) F_drag = 0.5 * rho * CD_0 * S

B

A44 = r44 * Ix

Ja_max

Single-screw propeller with 3 blades and blade-area ratio = 0.718. Coefficients are computed using the Matlab MSS toolbox: >> [KT_0, KQ_0] = wageningen(0,1,0.718,3) >> [KT_max, KQ_max] = wageningen(0.6632,1,0.718,3)

dynamics(u_control)[source]

Integrate 6-DOF nonlinear AUV equations of motion forward one time step.

Computes vehicle acceleration and control actuator responses under current state, control commands, and environmental conditions. Implements complete Fossen-based marine vehicle dynamics with rigid body, added mass, hydrodynamic, and environmental coupling effects. Uses Euler forward integration for computational efficiency.

Parameters:

u_control (ndarray, shape (3,)) –

Commanded control inputs [delta_r, delta_s, n]:

u_control[0]float, delta_r

Commanded rudder angle in radians. Positive deflection creates starboard turn (right when viewed from above). Limited to deltaMax_r.

u_control[1]float, delta_s

Commanded stern plane angle in radians. Positive deflection creates bow-down pitch moment. Limited to deltaMax_s.

u_control[2]float, n

Commanded propeller revolution rate in rpm. Positive values produce forward thrust. Limited to nMax.

Returns:

  • nu (ndarray, shape (6,)) – Updated vehicle velocity vector in body-fixed frame after the integration step [u, v, w, p, q, r]:

    nu[0]float, u

    Surge velocity (forward/aft) in m/s

    nu[1]float, v

    Sway velocity (port/starboard) in m/s

    nu[2]float, w

    Heave velocity (up/down) in m/s

    nu[3]float, p

    Roll rate about x-axis in rad/s

    nu[4]float, q

    Pitch rate about y-axis in rad/s

    nu[5]float, r

    Yaw rate about z-axis in rad/s

  • u_actual (ndarray, shape (3,)) – Actual control surface positions and propeller rate after actuator dynamics, time constants, and saturation limits [delta_r, delta_s, n]:

    u_actual[0]float, delta_r

    Actual rudder angle in radians

    u_actual[1]float, delta_s

    Actual stern plane angle in radians

    u_actual[2]float, n

    Actual propeller rpm

Return type:

Tuple[ndarray[Any, dtype[float64]], ndarray[Any, dtype[float64]]]

Notes

Equations of Motion:

The dynamics follow Fossen’s 6-DOF formulation:

M * d/dt nu_r + C(nu_r) * nu_r + D(nu_r) * nu_r + g(eta) = tau

where:

  • M: Mass matrix, M_RB + M_A (rigid body plus added mass)

  • d/dt nu_r: Relative acceleration

  • C(nu_r): Coriolis and centripetal matrix (function of relative velocity)

  • D(nu_r): Damping matrix (linear + quadratic drag)

  • g(eta): Restoring forces and moments (weight, buoyancy)

  • tau: Generalized force vector (propulsion + control surfaces)

  • nu_r: Relative velocity, nu - nu_c (accounting for ocean current)

Force and Moment Components:

  1. Propleller Thrust and Torque:

    • Wageningen B-series approximation

    • Thrust depends on advance number J_a = V_a/(nD_prop)

    • Coefficients: K_T0, K_Q0, K_Tmax, K_Qmax

    • Thrust deduction factor t_prop accounts for hull interaction

  2. Control Surface Forces:

    • Rudder: Generates sway force Y_r and yaw moment N_r

    • Stern planes: Generate heave force Z_s and pitch moment M_s

    • Lift coefficient times dynamic pressure times surface area

    • Includes drag penalty (parasitic drag)

  3. Lift and Drag:

    • Angle of attack alpha = atan2(w_r, u_r)

    • Lift and drag coefficients from Beard & McLain (2012)

    • Cross-flow drag for lateral motion

  4. Ocean Current Effects:

    • Ocean current velocity nu_c added in END frame

    • Relative velocity nu_r = nu - R^(T(psi) * nu_c) used for hydrodynamic forces

    • Derivative of current (Coriolis-like term) included

Actuator Dynamics:

First-order lag models with time constants:

d/dt delta_r = (delta_r,cmd - delta_r) / T_delta d/dt delta_s = (delta_s,cmd - delta_s) / T_delta d/dt n = (n_cmd - n) / T_n

where:

  • T_delta: rudder / stern plane time constant

  • T_n: propeller time constant

Safety and Collision Detection:

  • Surface breach (z < 0): Buoyancy set to zero, continues dynamics

  • Floor collision (z > z_floor): Vehicle immobilized, returns zero velocities

  • Immobilization flag set to True on floor collision, persists for simulation duration

Integration Method:

Forward Euler integration with step size h = sampleTime:

nu(k+1) = nu(k) + h * d/dt nu(k) u_actual(k+1) = u_actual(k) + h * d/dt u_actual(k)

This is computationally efficient but requires sufficiently small time steps, typically 0.02 s or smaller, for numerical stability.

Coordinate Frames:

  • BODY frame: Fixed to vehicle, origin at center of origin (CO)

  • END frame: East-North-Down inertial reference frame

  • All forces / moments computed in BODY frame

  • Velocity transformation via rotation matrix R(psi)

See also

gnc.m2c

Mass matrix to Coriolis matrix conversion

gnc.forceLiftDrag

Lift and drag force calculation

gnc.crossFlowDrag

Cross-flow drag calculation

gnc.gvect

Restoring force vector calculation

navigation.attitudeEuler

Attitude integration for position update

References

[1] Fossen, T.I. (2021). Handbook of Marine Craft Hydrodynamics and Motion Control. 2nd Edition, Wiley.

[2] Beard, R.W. and McLain, T.W. (2012). Small Unmanned Aircraft: Theory and Practice. Princeton University Press.

Examples

### Simulate one dynamics step with control commands:

>>> auv = Remus100s()
>>> auv.eta = np.array([0, 0, 10, 0, 0, 0])   # 10m depth
>>> auv.nu = np.array([2.0, 0, 0, 0, 0, 0])   # 2 m/s forward
>>> u_cmd = np.array([0.1, -0.05, 1200])      # rudder, stern, prop
>>> nu_new, u_act = auv.dynamics(u_cmd)
>>> print(f"New surge velocity: {nu_new[0]:.3f} m/s")
>>> print(f"Actual rudder angle: {u_act[0]:.3f} rad")
xferN2U(rpm)[source]

Transfer function from propller RPM to vehicle Speed.

Parameters:

rpm (float) – Number of propeller Rotations Per Minute.

Returns:

speed – Vehicle speen (m/s).

Return type:

float

Notes

Based on a simple linear speed test in a zero ocean current environment. The function domain is split into three regions with a linear approximation for each.

xferU2N(speed)[source]

Transfer function from vehicle Speed to propeller RPM.

Parameters:

speed (float) – Vehicle speed (m/s).

Returns:

rpm – Number of propller Rotations Per Minute.

Return type:

float

Notes

Based on a simple linear speed test in a zero ocean current environment. The function domain is split into three regions with a linear approximation for each.

collectSensorData(i, ocean)[source]

Update vehicle environmental state from installed sensors.

Main sensor data collection method called once per simulation iteration. Reads installed sensors and updates vehicle attributes with environmental measurements. This is the primary interface between the simulation environment and the vehicle’s internal state representation.

Parameters:
  • i (int) – Current simulation iteration counter. Used for time-dependent sensing, logging, and sensor dynamics. Typically ranges from 0 to N-1 where N is total simulation iterations.

  • ocean (env.Ocean) –

    Ocean environment object containing:

    • currentenv.OceanCurrent or None

      Ocean current model with speed and direction

    • floorenv.OceanFloor or None

      Ocean floor depth model (bathymetry)

    • Additional environment features as available

Return type:

None

Notes

Side Effects:

Updates the following vehicle attributes based on sensor readings:

  • drift_cfloat

    Ocean current speed in m/s (from ‘current’ sensor if installed)

  • set_cfloat

    Ocean current direction in radians (from ‘current’ sensor if installed)

  • seabed_zfloat

    Ocean floor depth in meters (from ‘depth’ sensor if installed)

Implementation:

Calls readAllSensors with the current environment kwargs, then maps the returned data dictionary to the corresponding vehicle attributes. Only sensors that are installed and return data will update vehicle state. The default sensors and their state mappings are:

  • ‘current’ -> self.drift_c, self.set_c

  • ‘depth’ -> self.seabed_z

Extensibility:

To add additional sensors and state updates:

  1. Define a sensor that inherits nav.Sensor

  2. Install sensor via addSensor()

  3. Add a corresponding attribute update below

Simulator Integration:

This method is called by the Simulator during each iteration of the simulation loop, specifically in simulate(), simulateMuNet(), and simulateAquaNet() methods. The call occurs after communication updates but before GNC computations.

See also

addSensor

Add single sensor

addSensors

Add multiple sensors at once from dictionary

removeSensor

Remove sensor by name

removeSelectedSensors

Remove multiple sensors by name list

removeAllSensors

Remove all sensors at

readSensor

Read data from specific sensor

readSelectedSensors

Read multiple sensors by name list

readAllSensors

Read data from all installed sensors

updateSensorInfo

Helper that updates info dictionary

loadPathFollowing()[source]

Configure vehicle for waypoint-based path following guidance system.

Sets up a complete autonomous navigation system for following a predefined sequence of waypoints. Configures all necessary guidance, navigation, and control components for integrated path-following behavior.

Notes

Side Effects:

  • Assigns function handles to the following vehicle attributes:

    • Guidance System:

      • self.GuidSystemcallable

        Main guidance system to coordinate components at a high-level.

      • self.GuidLawcallable

        Core guidance algorithm implementing specific approach for path generation.

    • Navigation Observers:

      • self.DepthObscallable

        Depth command filter and state estimator.

      • self.HeadingObs:

        Heading state estimator and reference generator.

    • Control Autopilots:

      • self.DepthAPcallable

        Depth autopilot implementing control commands for stern plane deflection.

      • self.HeadingAPcallable

        Heading autopilot implementing control commands for rudder defleciton.

  • Updates the vehicle’s info dictionary with configuration details for display and logging.

Configuration Options:

Currently there is only one set of configuration options available for the path following guidance system, the Adaptive Line-of-Sight (ALOS) guidance law. See guidance.ALOSlaw for specific details.

Attributes used by the assigned components can be customized by setting them manually. For example:

### Modify Guidance System Parameters:

>>> auv.loadPathFollowing()
>>> auv.Delta = 15.0    # Larger look-ahead distance
>>> auv.R_switch = 5.0  # Tighter waypoint acceptance distance

See each assigned function for more details and additional configuration options.

See also

guidance.pathFollow

Main path-following guidance function

guidance.ALOSlaw

Adaptive line-of-sight guidance law

navigation.depthFilter

Depth measurement filter

navigation.headingFilterLOS

LOS angle observer

control.depthPID

Depth autopilot with cascade control

control.headingPID

Heading autopilot

guidance.Waypoint

Waypoint database class

loadTargetTracking

Alternative guidance for swarm following

loadConstantProp

Propeller command configuration

References

[1] Fossen, T. I., “An Adaptive Line-of-Sight (ALOS) Guidance Law for Path Following of Aircraft and Marine Craft,” in IEEE Transactions on Control Systems Technology, 31(6), 2887-2894, Nov. 2023, doi: 10.1109/TCST.2023.3259819.

[2] Fossen, T.I. (2021). Handbook of Marine Craft Hydrodynamics and Motion Control. 2nd Edition, Wiley.

Examples

### Basic path following setup:

>>> auv = Remus100s()
>>> auv.wpt = guid.Waypoint(     # Define waypoint path
...     [0, 100, 200, 300],      # x coordinates (East)
...     [0, 0, 100, 100],        # y coordinates (North)
...     [10, 10, 10, 10]         # z coordinates (Down / Depth)
... )
>>> auv.loadPathFollowing()      # Configure path following
>>> print(auv.info['Guidance System'])
'Path Following, ALOS'
Return type:

None

loadTargetTracking(target, law='APF', mission='targetFeedforward', formation='targetNormPoly', survival='groupNormPoly')[source]

Configure vehicle for swarm target tracking.

Sets up autonomous target-following behavior for swarm coordination using specified guidance law.

Parameters:
  • target (Vehicle) – Target vehicle to track and follow. The target’s position and veloctiy are tracked for coordinated motion.

  • law (str) –

    Guidance law selection:

    • ’APF’: Artificial Potential Field guidance

    • ’CB’: Constant Bearing guidance

  • mission (str) –

    APF mission control component:

    • ’targetFeedforward’: Feed-forward target vehicle velocity vector.

  • formation (str) –

    APF Formation keeping component:

    • ’targetNormPoly’: Radial attraction and repulsion to target.

  • survival (str) –

    APF Collision avoidance component:

    • ’groupNormPoly’: Repulsion from all swarm group vehicles.

Return type:

None

Notes

Side Effects:

  • Assigns function handles to the following vehicle attributes:

    • Guidance System:

      • self.GuidSystemcallable

        Main guidance system to coordinate components at a high-level.

      • self.GuidLawcallable

        Core guidance algorithm implementing specific approach for path generation.

    • APF Component Functions (if law=’APF’):

      • self.GuidLaw.missioncallable

        Contributes to mission-based control velocity vector.

      • self.GuidLaw.formationcallable

        Artificial potential that contributes to formation keeping.

      • self.GuidLaw.survivalcallable

        Artificial potential that contributes to collision avoidance.

    • Control Autopilots:

      • self.DepthAPcallable

        Depth autopilot implementing control commands for stern plane deflection.

      • self.HeadingAPcallable

        Heading autopilot implementing control commands for rudder defleciton.

    See assigned functions for details and configuration options.

  • Updates the vehicles target attribute. Uses the passed Vehicle instance if no CommNetwork, otherwise creates a Model instance (a lightweight representation for tracking data).

  • Updates the vehicles groupId attribute, inheriting from the target vehicle.

  • Updates the vehicle’s info dictionary with configuration details for display and logging.

Swarm Coordination Parameters:

The following vehicle attributes control swarm behavior:

  • r_safefloat

    Minimum safe separation distance, triggers strong repulsion

  • r_avoidfloat

    Avoidance radius, repulsion active within this range

  • r_innerfloat

    Inner radius of neutral zone around preferred following distance

  • r_followfloat

    Preferred following distance from target

Tune these parameters based on:

  • Vehicle size and maneuverability

  • Communication latency and update rate

  • Environmental conditions (currents, obstacles)

  • Desired formation tightness

Depth Control Difference:

Unlike path following which uses cascade depth control, target tracking uses direct pitch control. This provides:

  • Faster depth response for dynamic target following

  • Direct 3D tracking without waypoint constraints

  • More aggressive maneuvering capability

See also

guidance.targetTrack

Main target tracking guidance function

guidance.velocitySubsumptionCascadeAPF

APF guidance law

guidance.velCB

Constant bearing velocity guidance law

guidance.missionTargetFeedForwardAPF

Target velociy feed-forward

guidance.formationTargetNormPolyAPF

Target attraction & repulsion

guidance.survivalGroupNormPolyAPF

Group member repulsion

control.pitchPID

Direct pitch controller

control.headingPID

Heading autopilot

loadPathFollowing

Alternative guidance for waypoint following

loadMuNetFdmaLF

Communication setup for swarm coordination

Examples

### Basic leader-follower setup with default APF:

>>> leader = Remus100s(groupId='A', isLeader=True)
>>> leader.wpt = guid.Waypoint([0, 100], [0, 0], [0, 20])
>>> leader.loadPathFollowing()
>>> follwer = Remus100s()
>>> follwer.loadTargetTracking(leader)
>>> print(follower.info['Target'])
A01-LEADER
loadConstantProp(n_setpt=1200)[source]

Configure constant propeller RPM command.

Sets up a simple propeller control that maintains constant RPM throughout simulation. Useful for basic testing and scenarios with fixed thrust.

Parameters:

n_setpt (float) – Propeller RPM setpoint (default: 1200 rpm, ~2.0 m/s forward speed).

Return type:

None

Notes

Assigns ctrl.constProp to self.PropCmd and stores n_setpt. Does not implement thrust control or speed regulation.

loadAquaNetTdmaLF(epDur=10, bcDur=1, rpDur=1)[source]

Configure TDMA communication via AquaNet for leader-follower swarm.

Parameters:
  • epDur (float) – Episode cycle duration in seconds (full comm cycle period).

  • bcDur (float) – Broadcast/request frame duration in seconds (leader transmit time).

  • rpDur (float) – Response frame duration in seconds (follower slot time).

Return type:

None

Notes

  • Sets up the Episode structure, which is the full set of transmission frames.

  • The Episode starts with the Leader Broadcast / Request (BCRQ) frame, followed by a Response (RSPN) frame for each follower.

  • Configures network addresses, message schedules, and communication manager.

loadMuNetLF(network, **kwargs)[source]

Configure communication via MuNet for leader-follower swarm.

Parameters:
  • network (comm.MuNet) – MuNet network object to register vehicle with

  • **kwargs (dict) –

    Configuration options:

    • accessModestr

      Network access mode (‘fdma’, ‘tdma’, ‘tdma_lf’)

    • epDurfloat

      Episode Duration (s). Vehicle message transmission interval

    • bcDurfloat

      TDMA - Broadcast-Request frame duration (s). (Leader)

    • rpDurfloat

      TDMA - Response frame duration (s). (Followers)

    • txOsetfloat

      FDMA - Transmit offset (s). Time between each vehicle reporting.

Return type:

None

Notes

  • Supports FDMA and TDMA access modes for flexible swarm communication.

  • Registers vehicle with network and configures message timing parameters.

munetauvsim.vehicles.buildGroup(num, gid, hasLeader=True, vehType=<class 'munetauvsim.vehicles.Remus100s'>, **kwargs)[source]

Create a list of vehicle instances for swarm simulation.

Parameters:
  • num (int) – Number of vehicles in the group.

  • gid (str) – Group identifier, single character (e.g., “A”).

  • hasLeader (bool) – If True, first vehicle in list is generated with isLeader=True.

  • vehType (type) – Vehicle class to instantiate (default: Remus100s).

  • **kwargs (dict) – Optional keyword arguments to pass to vehicle constructor.

Returns:

group (list of Vehicle) – List of initialized vehicle objects with consistent group ID. If hasLeader=True, group[0].isLeader is True.

Return type:

List[Vehicle]

Notes

Parameter Inheritance:

All vehicles in the group receive the same groupId and any keyword attributes passed in kwargs. The hasLeader parameter will only set isLeader=True for the first vehicle in the returned list.

Vehicle Numbering:

Vehicle IDs are assigned sequentially based on the class counter to avoid any duplicate vehicle IDs in a single session.

Examples

### Basic group with default parameters:

>>> swarm = buildGroup(5, "A", True)
>>> for auv in swarm:
...     print(auv.callSign)
...
A01-LEADER
A02
A03
A04
A05

### Group with custom vehicle parameters:

>>> swarm = buildGroup(
...     num=3,
...     gid="B",
...     hasLeader=True,
...     vehType=Remus100s,
...     r_safe=15.0,
...     r_avoid=50.0
... )
>>> print(swarm[0].sampleTime)
0.01
>>> print(swarm[1].r_safe)
15.0

### Group without leader:

>>> swarm = buildGroup(5, "C", hasLeader=False)
>>> print(swarm[0].isLeader)
False