robotpy_toolkit_7407.subsystem_templates.drivetrain package

Submodules

robotpy_toolkit_7407.subsystem_templates.drivetrain.differential_drivetrain module

class robotpy_toolkit_7407.subsystem_templates.drivetrain.differential_drivetrain.DifferentialDrivetrain

Bases: Subsystem

Extendable differential drivetrain class.

Args:

m_left: leading left motor m_right: leading right motor axis_x: x-axis of the joystick axis_y: y-axis of the joystick gear_ratio: gear ratio of the drivetrain

axis_x: JoystickAxis = None
axis_y: JoystickAxis = None
gear_ratio: float
init()

Initialize the drivetrain.

m_left: PIDMotor = None
m_right: PIDMotor = None
set_motor_percent_output(left: float, right: float)

Set the percent output of the motors between -1 and 1

Args:

left (float): percent output of the left motor right (float): percent output of the right motor

set_motor_velocity(left_vel: float, right_vel: float)

Set the velocity of the motors in meters per second

Args:

left_vel (meters_per_second): velocity of the left motor right_vel (meters_per_second): velocity of the right motor

robotpy_toolkit_7407.subsystem_templates.drivetrain.differential_drivetrain_commands module

class robotpy_toolkit_7407.subsystem_templates.drivetrain.differential_drivetrain_commands.DriveArcade(subsystem: T, track_width_inches: float)

Bases: SubsystemCommand[DifferentialDrivetrain]

Arcade drive command for differential drivetrain.

end(self: commands2._impl.Command, interrupted: bool) None

The action to take when the command ends. Called when either the command finishes normally, or when it interrupted/canceled.

Parameters:

interrupted – whether the command was interrupted/canceled

execute(self: commands2._impl.Command) None

The main body of a command. Called repeatedly while the command is scheduled.

initialize(self: commands2._impl.Command) None

The initial subroutine of a command. Called once when the command is initially scheduled.

isFinished(self: commands2._impl.Command) bool

Whether the command has finished. Once a command finishes, the scheduler will call its end() method and un-schedule it.

Returns:

whether the command has finished.

runsWhenDisabled(self: commands2._impl.Command) bool

Whether the given command should run when the robot is disabled. Override to return true if the command should run when disabled.

Returns:

whether the command should run when the robot is disabled

robotpy_toolkit_7407.subsystem_templates.drivetrain.swerve_drivetrain module

class robotpy_toolkit_7407.subsystem_templates.drivetrain.swerve_drivetrain.SwerveDrivetrain

Bases: Subsystem

Swerve Drivetrain Extendable class. Contains driving functions.

axis_dx: JoystickAxis
axis_dy: JoystickAxis
axis_rotation: JoystickAxis
deadzone_angular_velocity: float = 0.08726646259971647
deadzone_velocity: float = 0.05
get_heading() Rotation2d

Get the robot heading.

Returns:

Heading (Rotation2d): the robot heading

gyro: SwerveGyro
init()

Initialize the swerve drivetrain, kinematics, odometry, and gyro.

max_angular_vel: float = 25.132741228718345
max_vel: float = 8.940777777777777
n_00: SwerveNode
n_01: SwerveNode
n_10: SwerveNode
n_11: SwerveNode
set_driver_centric(vel: (<class 'float'>, <class 'float'>), angular_vel: float)

Set the driver centric velocity and angular velocity. Driver centric runs with perspective of driver.

Args:

vel: velocity in x and y direction as (meters per second, meters per second) angular_vel: angular velocity in radians per second

set_robot_centric(vel: (<class 'float'>, <class 'float'>), angular_vel: float)

Set the robot centric velocity and angular velocity. Robot centric runs with perspective of robot. Args:

vel: velocity in x and y direction as (meters per second, meters per second) angular_vel: angular velocity in radians per second

start_pose: Pose2d = Pose2d(Translation2d(x=0.000000, y=0.000000), Rotation2d(0.000000))
stop()

Stop the drivetrain and all pods.

track_width: float = 1
class robotpy_toolkit_7407.subsystem_templates.drivetrain.swerve_drivetrain.SwerveGyro

Bases: object

Extendable class for swerve gyro.

get_robot_heading() float

Get the robot heading in radians. Overridden class. Must return radians.

init()

Initialize the swerve gyro. Overridden class.

reset_angle()

Reset the robot heading. Overridden class.

class robotpy_toolkit_7407.subsystem_templates.drivetrain.swerve_drivetrain.SwerveNode

Bases: object

Extendable class for swerve node.

get_current_motor_angle() float

Get the current angle of the swerve node. Must be overridden. Must return radians.

get_drive_motor_traveled_distance() float

Get the distance traveled by the drive motor. Must be overridden. Must return meters.

get_motor_velocity() float

Get the velocity of the swerve node. Must be overridden. Must return meters per second.

get_node_position() SwerveModulePosition

Get the position of the swerve node.

Returns:

SwerveModulePosition: position of the swerve node

get_node_state() SwerveModuleState

Get the state of the swerve node. Returns:

SwerveModuleState: state of the swerve node

get_turn_motor_angle() float

Get the distance traveled by the turning motor. Must be overridden. Must return radians. (0, 2π)

init()

Initialize the swerve node.

motor_reversed: bool = False
motor_sensor_offset: float = 0
set(vel: float, angle_radians: float)

Set the velocity and angle of the swerve node.

Args:

vel (meters_per_second): velocity of the swerve node angle_radians (radians_per_second): turning swerve node velocity in radians per second

set_motor_angle(pos: float)

Set the angle of the swerve node. Must be overridden.

Args:

pos (radians): angle of the swerve node in radians

set_motor_velocity(vel: float)

Set the velocity of the swerve node. Must be overridden. Args:

vel (meters_per_second): velocity of the swerve node in meters per second

robotpy_toolkit_7407.subsystem_templates.drivetrain.swerve_drivetrain_commands module

class robotpy_toolkit_7407.subsystem_templates.drivetrain.swerve_drivetrain_commands.DriveSwerve(subsystem: T)

Bases: SubsystemCommand[SwerveDrivetrain]

Drive the robot using a swerve drive controller.

end(self: commands2._impl.Command, interrupted: bool) None

The action to take when the command ends. Called when either the command finishes normally, or when it interrupted/canceled.

Parameters:

interrupted – whether the command was interrupted/canceled

execute() None

Execute the command. Can be overridden for a custom swerve drive.

initialize(self: commands2._impl.Command) None

The initial subroutine of a command. Called once when the command is initially scheduled.

isFinished(self: commands2._impl.Command) bool

Whether the command has finished. Once a command finishes, the scheduler will call its end() method and un-schedule it.

Returns:

whether the command has finished.

runsWhenDisabled(self: commands2._impl.Command) bool

Whether the given command should run when the robot is disabled. Override to return true if the command should run when disabled.

Returns:

whether the command should run when the robot is disabled

class robotpy_toolkit_7407.subsystem_templates.drivetrain.swerve_drivetrain_commands.FollowPath(subsystem: SwerveDrivetrain, trajectory: Trajectory, period: float = 0.02)

Bases: SubsystemCommand[SwerveDrivetrain]

Follow a given wpimath trajectory using a swerve drive controller.

end(self: commands2._impl.Command, interrupted: bool) None

The action to take when the command ends. Called when either the command finishes normally, or when it interrupted/canceled.

Parameters:

interrupted – whether the command was interrupted/canceled

execute(self: commands2._impl.Command) None

The main body of a command. Called repeatedly while the command is scheduled.

initialize(self: commands2._impl.Command) None

The initial subroutine of a command. Called once when the command is initially scheduled.

isFinished(self: commands2._impl.Command) bool

Whether the command has finished. Once a command finishes, the scheduler will call its end() method and un-schedule it.

Returns:

whether the command has finished.

runsWhenDisabled(self: commands2._impl.Command) bool

Whether the given command should run when the robot is disabled. Override to return true if the command should run when disabled.

Returns:

whether the command should run when the robot is disabled

Module contents