seamonsters

class seamonsters.AccelerationFilter(linearAccel, angularAccel)

Bases: object

Calculates acceleration filtering for drive inputs (magnitude, direction, turn).

__init__(linearAccel, angularAccel)[source]
Parameters
  • linearAccel – Linear acceleration, in feet per second per second

  • angularAccel – Angular acceleration, in radians per second per second

filter(magnitude, direction, turn)[source]
Parameters
  • magnitude – linear velocity in feet per second

  • direction – linear direction in radians

  • turn – angular velocity in radians per second

Returns

tuple of filtered magnitude, direction, turn

class seamonsters.AddParallelSignal(iterable)

Bases: seamonsters.ParallelSignal

Value to signal that a new generator should be added to the group of parallel commands.

__init__(iterable)[source]

Initialize self. See help(type(self)) for accurate signature.

class seamonsters.AngledWheel(motor: rev._rev.CANSparkMax, x, y, angle, circumference, maxVoltageVelocity, reverse=False)

Bases: seamonsters.Wheel

An AngledWheel is a wheel oriented in a fixed direction, which it can’t change on its own. It uses a SparkMax to drive.

__init__(motor: rev._rev.CANSparkMax, x, y, angle, circumference, maxVoltageVelocity, reverse=False)[source]
Parameters
  • motors – a SparkMax

  • x – X position in feet

  • y – Y position in feet

  • angle – radians, direction of force. 0 is right, positive counter-clockwise

  • circumference – wheel circumference in feet

  • maxVoltageVelocity – velocity at 100% in voltage mode, in feet per second

  • reverse – boolean, optional

addMotor(motor: rev._rev.CANSparkMax)[source]
changeGear(gearRatio)[source]
disable()[source]

Disable motors. Calling drive() will enable them again.

getRealDirection()[source]
Returns

the current direction the wheel is moving in radians. This may

be based on sensors.

getRealPosition()[source]
Returns

a value representing distance the wheel has travelled, which

accumulates over the lifetime of the wheel.

getRealVelocity()[source]
Returns

the current velocity of the wheel in feet per second, based on

sensors.

getTargetDirection()[source]
Returns

target value for getRealDirection()

getTargetPosition()[source]
Returns

target value for getRealPosition() – where wheel is

moving to

limitMagnitude(magnitude, direction)[source]

Return the scaling factor necessary to keep the wheel speed within its limits.

Parameters
  • magnitude – speed in feet per second

  • direction – radians. 0 is right, positive counter-clockwise

Returns

1.0 if wheel speed is within it limits, otherwise a value between 0 and 1 to scale the wheel down to its maximum speed.

resetPosition()[source]
setIdleMode(mode)[source]
class seamonsters.CasterWheel(x, y)

Bases: seamonsters.Wheel

Doesn’t drive a motor, only stores its drive parameters and echoes them back for getRealDirection and getRealVelocity.

__init__(x, y)[source]
Parameters
  • x – X offset from origin in feet

  • y – Y offset from origin in feet

getRealDirection()[source]
Returns

the current direction the wheel is moving in radians. This may

be based on sensors.

getRealPosition()[source]
Returns

a value representing distance the wheel has travelled, which

accumulates over the lifetime of the wheel.

getRealVelocity()[source]
Returns

the current velocity of the wheel in feet per second, based on

sensors.

getTargetDirection()[source]
Returns

target value for getRealDirection()

getTargetPosition()[source]
Returns

target value for getRealPosition() – where wheel is

moving to

class seamonsters.Dashboard(*args, css=False, **kwargs)

Bases: remi.server.App

Adds some utilities for building robot dashboards to remi.App.

A dashboard class must have a main function which takes robot and appCallback as arguments, where robot is the robot object and appCallback is a function that should be called with self as an argument when main has completed.

Parameters

css – Whether to use a custom css file. Must be located at ‘res/style.css’

__init__(*args, css=False, **kwargs)[source]

Initialize self. See help(type(self)) for accurate signature.

clearEvents()[source]

Clear the event queue without executing any events. It’s a good idea to call this at the start of teleop, in case someone clicked some buttons while the robot was disabled.

doEvents()[source]

Execute all events in the event queue and clear the queue. This should be called continuously during teleop.

class seamonsters.DynamicAxis(exponent=1.0, speedScaleFactor=0.0, speedScaleExponent=0.0, deadZone=None)

Bases: object

Makes values from a joystick axis go higher if you push them faster.

__init__(exponent=1.0, speedScaleFactor=0.0, speedScaleExponent=0.0, deadZone=None)[source]

exponent should be >= 1. speedScaleFactor should be >= 1. speedScaleExponent should be <= 1 (use 0 to ignore speed). deadZone should be < 1 and close to 0.

update(value)[source]

Update the value of the axis

Parameters

value – the raw axis value from the joystick

Returns

the adjusted value

class seamonsters.Gamepad(port)

Bases: wpilib._wpilib.Joystick

An extended Joystick specifically designed for Logitech gamepads. It adds dead zones and changes positive x to direction 0. The gamepad mode switch MUST be at X!

The Gamepad class has constants defined for the numbers of gamepad buttons. These include the colored A, B, X, and Y buttons; the left and right bumpers; the left and right triggers; the left and right joysticks when pressed; the Back and Start buttons; and the 4 d-pad buttons. The state of these buttons can be checked with gamepad.getRawButton(Gamepad.BUTTON_CONSTANT).

For more of Gamepad’s supported methods, see wpilib.joystick

A = 1
B = 2
BACK = 7
DOWN = 14
LB = 5
LEFT = 15
LJ = 9
LT = 11
RB = 6
RIGHT = 16
RJ = 10
RT = 12
START = 8
TRIGGER_THRESHOLD = 0.5
UP = 13
X = 3
Y = 4
__init__(self: wpilib._wpilib.Joystick, port: int) → None[source]

Construct an instance of a joystick.

The joystick index is the USB port on the Driver Station.

Parameters

port – The port on the Driver Station that the joystick is plugged into (0-5).

getButtonCount(self: wpilib.interfaces._interfaces.GenericHID) → int[source]

Get the number of buttons for the HID.

Returns

the number of buttons on the current HID

getDPad()[source]

Return the currently pressed direction of the d-pad. -1 is not pressed. 0 - 7 represents the directions starting at Up and moving clockwise.

getLDirection()[source]

Get the direction of the left joystick. wpilib.Joystick’s built-in getDirection() says 0 is positive y. This version uses positive x.

getLMagnitude()[source]

Get the magnitude of the left joystick. The dead zone is enabled by default; set enableDeadZone to False to disable it.

getLTrigger()[source]

Get how far the left trigger is pressed, as a value from 0.0 to 1.0

getLX()[source]

Get the x-axis of the left joystick. The dead zone is enabled by default; set enableDeadZone to False to disable it.

getLY()[source]

Get the y-axis of the left joystick. The dead zone is enabled by default; set enableDeadZone to False to disable it.

getRDirection()[source]

Get the direction of the right joystick. wpilib.Joystick’s built-in getDirection() says 0 is positive y. This version uses positive x.

getRMagnitude()[source]

Get the magnitude of the right joystick. The dead zone is enabled by default; set enableDeadZone to False to disable it.

getRTrigger()[source]

Get how far the right trigger is pressed, as a value from 0.0 to 1.0

getRX()[source]

Get the x-axis of the right joystick. The dead zone is enabled by default; set enableDeadZone to False to disable it.

getRY()[source]

Get the y-axis of the right joystick. The dead zone is enabled by default; set enableDeadZone to False to disable it.

getRawButton(self: wpilib.interfaces._interfaces.GenericHID, button: int) → bool[source]

Get the button value (starting at button 1).

The buttons are returned in a single 16 bit value with one bit representing the state of each button. The appropriate button is returned as a boolean value.

Parameters

button – The button number to be read (starting at 1)

Returns

The state of the button.

getRawLMagnitude()[source]
getRawLX()[source]
getRawLY()[source]
getRawRMagnitude()[source]
getRawRX()[source]
getRawRY()[source]
inDeadZone(value)[source]

Check if a value between -1 and 1 is within the position deadzone. Return a boolean value.

lInDeadZone()[source]

Check if the left joystick is in the deadzone. Return a boolean value.

rInDeadZone()[source]

Check if the right joystick is in the deadzone. Return a boolean value.

class seamonsters.GeneratorBot

Bases: wpilib._wpilib.RobotBaseUser

A robot which runs generators throughout the cycles of autonomous, teleop, and test mode. The generators are iterated 50 times per second, synchronized with the rate that data is received from Driver Station.

__init__(self: wpilib._wpilib.RobotBaseUser) → None[source]
autonomous()[source]

Override this to make a generator for autonomous

free()[source]
logger = <Logger robot (WARNING)>
period = 0.02
robotInit()[source]

Override this for robot initialization. This should NOT be a generator.

startCompetition(self: wpilib._wpilib.RobotBase) → None[source]
teleop()[source]

Override this to make a generator for teleop

test()[source]

Override this to make a generator for test mode

class seamonsters.IterativeRobotInstance(robotType)

Bases: object

Allows an “instance” of an IterativeRobot to be created without connecting to HAL. Allows running teleop/autonomous sequences as a Generator.

__init__(robotType)[source]

Initialize self. See help(type(self)) for accurate signature.

autonomousGenerator()[source]

A generator which runs autonomousInit then autonomousPeriodic continuously.

teleopGenerator()[source]

A generator which runs teleopInit then teleopPeriodic continuously.

class seamonsters.MecanumWheel(motor: rev._rev.CANSparkMax, x, y, angle, circumference, maxVoltageVelocity, reverse=False)

Bases: seamonsters.AngledWheel

An angled Mecanum wheel. The velocity of the wheel is scaled up to compensate for the effect of the rollers. For the angle of the wheel, use the diagonal direction of force in the diamond pattern.

SQRT_2 = 1.4142135623730951
getRealPosition()[source]
Returns

a value representing distance the wheel has travelled, which

accumulates over the lifetime of the wheel.

getRealVelocity()[source]
Returns

the current velocity of the wheel in feet per second, based on

sensors.

getTargetPosition()[source]
Returns

target value for getRealPosition() – where wheel is

moving to

limitMagnitude(magnitude, direction)[source]

Return the scaling factor necessary to keep the wheel speed within its limits.

Parameters
  • magnitude – speed in feet per second

  • direction – radians. 0 is right, positive counter-clockwise

Returns

1.0 if wheel speed is within it limits, otherwise a value between 0 and 1 to scale the wheel down to its maximum speed.

class seamonsters.MultiDrive(superDrive)

Bases: object

Wraps a SuperHolonomicDrive, and allows drive() to be called multiple times in a loop. The values for all of these calls are added together, and sent to the SuperHolonomicDrive when update() is called.

__init__(superDrive)[source]

Initialize self. See help(type(self)) for accurate signature.

drive(magnitude, direction, turn)[source]
update()[source]
class seamonsters.ParallelSignal

Bases: object

A signal that can be returned from a generator in a parallel group to trigger an action on the group.

class seamonsters.PathFollower(drive, ahrs=None)

Bases: object

Controls a SuperHolonomicDrive to follow paths on the field.

NAVX_ERROR_CORRECTION = 0.1
NAVX_LAG = 7
__init__(drive, ahrs=None)[source]
Parameters
  • drive – a SuperHolonomicDrive

  • x – starting x position of the robot, in feet

  • y – starting y position of the robot, in feet

  • angle – starting angle of the robot, radians. 0 means the robot’s local XY coordinates line up with the field XY coordinates.

  • ahrs – an optional AHRS (NavX) instance. If provided, this will be used to track the robot’s rotation; if not, the rotation will be calculated based on the movement of the motors.

driveToPointGenerator(x, y, finalAngle=None, speed=1, robotPositionTolerance=0, robotAngleTolerance=0)[source]

A generator to drive to a location on the field while simultaneously pointing the robot in a new direction. This will attempt to move the robot so it reaches the target position at a given speed and ends by rotating to the inputted angle. This generator never exits, but yields True or False if the robot is close enough to its target position, within tolerance.

setPosition(x, y, angle)[source]
updateRobotPosition()[source]
class seamonsters.State(function, subMachine=None)

Bases: object

An action to run in a StateMachine.

__init__(function, subMachine=None)[source]
Parameters
  • function – A function with no arguments that returns a generator. If the generator returns another State, that State will be pushed to the stack. Otherwise the State will be popped when it completes.

  • subMachine – Optional, another StateMachine to run in parallel with this State. Allows States to have nested sub-States.

runState()[source]
class seamonsters.StateMachine

Bases: object

Implementation of a Pushdown Automaton. Has one state always running at a time, and keeps track of a stack of states.

__init__()[source]

Initialize self. See help(type(self)) for accurate signature.

clear()[source]

Cancel the current state and clear the stack.

currentState()[source]

Get the current running state. If the state stack is empty, IDLE_STATE is the current state.

pop()[source]

Cancel the current running State and pop it. Run the State below it on the stack.

push(state)[source]

Cancel the current running State and push a new State to the stack.

replace(state)[source]

Cancel the current running state and replace it with a new one.

runUntilPopped(state)[source]

Push a state and wait until the state is popped from the stack.

runUntilStopped(state)[source]

Push a state and wait until the state is either cancelled by pushing or popping, or it exits normally.

updateGenerator()[source]

Generator to update the state machine.

class seamonsters.StopParallelSignal(value=None)

Bases: seamonsters.ParallelSignal

Value to signal that a group of parallel commands should be stopped.

__init__(value=None)[source]

Initialize self. See help(type(self)) for accurate signature.

class seamonsters.SuperHolonomicDrive

Bases: object

__init__()[source]

Initialize self. See help(type(self)) for accurate signature.

addWheel(wheel)[source]

Add a wheel to the set of drivetrain wheels. :param wheel: a Wheel

disable()[source]

Disable all motors. Calling drive() will enable them again.

drive(magnitude, direction, turn)[source]

Drive the robot. This should be called 50 times per second.

If drive is called with a magnitude/turn of 0 for more than autoDisableTime iterations, all wheels will be disabled.

Parameters
  • magnitude – feet per second

  • direction – radians. 0 is right, positive counter-clockwise

  • turn – radians per second. positive counter-clockwise

Returns

the scale of the actual output speed, as a fraction of the input magnitude and turn components

getRobotMovement()[source]

Get the movement of the robot as a whole, based on wheel sensors.

Returns

(magnitude, direction, turn). Magnitude in feet per second, direction in radians, turn in radians per second.

getRobotPositionOffset(origin, target=False)[source]

Calculate how the robot has moved from a previous position.

Parameters
  • origin – an object returned by a previous call to getRobotPositionOffset, for comparing previous state. Passing None will return an offset of 0 and a newly initialized state

  • targetPosition – if False, the “real” position of wheels will be used based on encoder values. If True, the target position of wheels will be used based on where they were last told to move.

Returns

a tuple of (distance, direction, turn, state) where distance and direction define linear offset in feet and radians, turn defines angular offset in radians, and state is an object that can be stored and passed to a future call of getRobotPositionOffset for comparison.

orientWheels(magnitude, direction, turn)[source]

Orient the wheels as if the robot was driving, but don’t move.

resetWheelPositions()[source]
undisable()[source]
class seamonsters.SwerveWheel(angledWheel: seamonsters.AngledWheel, steerMotor: rev._rev.CANSparkMax, encoderCountsPerRev, rotationVelocity, offsetX=0, offsetY=0, reverseSteerMotor=False)

Bases: seamonsters.Wheel

A wheel which can rotate. A SwerveWheel drives using an AngledWheel, and rotates using a SparkMax.

__init__(angledWheel: seamonsters.AngledWheel, steerMotor: rev._rev.CANSparkMax, encoderCountsPerRev, rotationVelocity, offsetX=0, offsetY=0, reverseSteerMotor=False)[source]

zeroSteering() is called in __init__.

Parameters
  • angledWheel – an AngledWheel for driving. Its angle will be updated as the swerve wheel rotates. The SwerveWheel will borrow its X/Y position when it’s initialized.

  • steerMotor – a SparkMax for rotating the swerve wheel. It should have a feedback sensor set for position mode.

  • encoderCountsPerRev – number of encoder counts in a full rotation of the steer motor

  • reverseSteerMotor – boolean, optional

disable()[source]

Disable motors. Calling drive() will enable them again.

getRealDirection()[source]
Returns

the current direction the wheel is moving in radians. This may

be based on sensors.

getRealPosition()[source]
Returns

a value representing distance the wheel has travelled, which

accumulates over the lifetime of the wheel.

getRealVelocity()[source]
Returns

the current velocity of the wheel in feet per second, based on

sensors.

getTargetDirection()[source]
Returns

target value for getRealDirection()

getTargetPosition()[source]
Returns

target value for getRealPosition() – where wheel is

moving to

limitMagnitude(magnitude, direction)[source]

Return the scaling factor necessary to keep the wheel speed within its limits.

Parameters
  • magnitude – speed in feet per second

  • direction – radians. 0 is right, positive counter-clockwise

Returns

1.0 if wheel speed is within it limits, otherwise a value between 0 and 1 to scale the wheel down to its maximum speed.

resetPosition()[source]
zeroSteering(currentAngle=0)[source]

Reset the origin (rotation of wheel when facing right) so that the current position of the steer motor is currentAngle (defaults 0).

class seamonsters.TFlightHotasX

Bases: object

Constants for the Thrustmaster T-Flight Hotas X joystick.

AXIS_LEVER = 4
AXIS_THROTTLE = 2
AXIS_TWIST = 3
AXIS_X = 0
AXIS_Y = 1
class seamonsters.TestWheel(name, x, y)

Bases: seamonsters.CasterWheel

Logs parameters for drive(), for testing.

__init__(name, x, y)[source]
Parameters
  • name – Name to include when logging parameters.

  • x – X offset from origin in feet

  • y – Y offset from origin in feet

disable()[source]

Disable motors. Calling drive() will enable them again.

class seamonsters.TimingMonitor

Bases: object

Monitors the rate of the update loop, to see how closely it matches 50Hz. Check fps for the measured number of iterations per second.

__init__()[source]

Initialize self. See help(type(self)) for accurate signature.

reset()[source]
step()[source]
updateGenerator()[source]
class seamonsters.ToggleButtonGroup

Bases: object

__init__()[source]

Initialize self. See help(type(self)) for accurate signature.

addButton(button=<class 'remi.gui.Button'>, key=None)[source]
highlight(key)[source]
class seamonsters.Wheel(x, y)

Bases: object

Interface for wheels. A Wheel has a location and can put out force in a direction.

__init__(x, y)[source]
Parameters
  • x – X offset from origin in feet

  • y – Y offset from origin in feet

disable()[source]

Disable motors. Calling drive() will enable them again.

drive(magnitude, direction, motorNum=None)[source]

Spin the wheel. This should be called 50 times per second.

Parameters
  • magnitude – speed in feet per second. Even if the magnitude is zero, the wheel will attempt to orient in the given direction

  • direction – radians. 0 is right, positive counter-clockwise

getRealDirection()[source]
Returns

the current direction the wheel is moving in radians. This may be based on sensors.

getRealPosition()[source]
Returns

a value representing distance the wheel has travelled, which accumulates over the lifetime of the wheel.

getRealVelocity()[source]
Returns

the current velocity of the wheel in feet per second, based on sensors.

getTargetDirection()[source]
Returns

target value for getRealDirection()

getTargetPosition()[source]
Returns

target value for getRealPosition() – where wheel is moving to

limitMagnitude(magnitude, direction)[source]

Return the scaling factor necessary to keep the wheel speed within its limits.

Parameters
  • magnitude – speed in feet per second

  • direction – radians. 0 is right, positive counter-clockwise

Returns

1.0 if wheel speed is within it limits, otherwise a value between 0 and 1 to scale the wheel down to its maximum speed.

resetPosition()[source]
stop()[source]

Stop driving.

seamonsters.circleDistance(a, b, circle=6.283185307179586)

Returns the shortest arc length between two points on a circle. Positive if direction is positive from a to b.

Parameters

circle – Total arc length of the circle. Optional, defaults to 2 pi.

seamonsters.deadZone(value, deadZone=0.1, maxValue=1.0)

Add a dead-zone to the number. Any input from deadZone to maxValue is mapped to the range 0 to maxValue. Negative numbers are also mapped. Any input between deadZone and -deadZone is mapped to 0.

Parameters
  • value – input number

  • deadZone – the minimum “dead zone” value

  • maxValue – the maximum value

Returns

the number, constrained to the minimum/maximum values

seamonsters.ensureFalse(iterable, requiredCount)

Wait until the iterable yields False for a certain number of consecutive iterations before finishing.

Returns

the return value of the iterable if it exits early, False otherwise (note difference from ensureTrue)

seamonsters.ensureTrue(iterable, requiredCount)

Wait until the iterable yields True for a certain number of consecutive iterations before finishing.

Returns

the return value of the iterable if it exits early, True otherwise

seamonsters.feedbackLoopScale(value, scale, exponent=1, maxValue=None)
seamonsters.forever()

Iterate forever.

seamonsters.getRobotPath(*paths)
seamonsters.hBoxWith(*args, **kwargs)

Construct a REMI HBox with the given keyword arguments, and add all of the given widgets to it.

seamonsters.parallel(*iterables)

Run a group of iterables in parallel. Ends when none are left running.

An iterable can yield or return a ParallelSignal to trigger an action.

seamonsters.queuedDashboardEvent(eventF)

Given a function eventF which takes any number of arguments, returns a new function which will add eventF and given arguments to the Dashboard event queue, to be called later.

seamonsters.readDataFile(filename)
seamonsters.returnValue(iterable, value)

Run an iterable but change the return value.

Returns

value

seamonsters.sequence(*iterables)

Run a set of iterables sequentially

seamonsters.setSimulatedDrivetrain(drivetrain)
seamonsters.startDashboard(robot, dashboardClass)

Start the dashboard in a separate thread. Behavior of this function will depend on the RobotPy command line arguments – in “run” mode the server will be started quietly, in “sim” mode a web browser will also be opened, and in “deploy” mode nothing will happen.

Parameters
  • robot – a robot object with an app variable. This will be set when the dashboard has started.

  • dashboardClass – a class which extends from sea.Dashboard

seamonsters.stopAllWhenDone(iterable)

If run in a sea.parallel block, when the iterable completes all parallel commands will be stopped.

seamonsters.timeLimit(iterable, time)

Run the iterable until it finishes or the given time limit has passed. Return the value of the iterable if it ends early, None otherwise.

seamonsters.untilButtonPressed(joystick, button)

A generator which runs until the joystick button is pressed, then exits.

Parameters
  • joystick – a wpilib.Joystick

  • button – a button number

seamonsters.untilTrue(iterable)

Run the iterable until it yields True, then stop.

seamonsters.vBoxWith(*args, **kwargs)

Construct a REMI VBox with the given keyword arguments, and add all of the given widgets to it.

seamonsters.wait(time)

Wait for a certain number of iterations.

seamonsters.whileButtonPressed(joystick, button)

A generator which runs while the joystick button is pressed, then exits.

Parameters
  • joystick – a wpilib.Joystick

  • button – a button number