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

Python examples #24

Merged
merged 18 commits into from
Feb 13, 2024
Merged
Show file tree
Hide file tree
Changes from 10 commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
26 changes: 25 additions & 1 deletion .github/workflows/build-all-parallel.yml
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ jobs:
container: wpilib/roborio-cross-ubuntu:2024-22.04

steps:
- uses: actions/checkout@v3
- uses: actions/checkout@v4

# Grant execute permission for gradlew
- name: Grant execute permission for gradlew
Expand All @@ -90,3 +90,27 @@ jobs:
# Runs a single command using the runners shell
- name: Compile and run tests on robot code for project ${{ matrix.project-name }}
run: cd "${{ matrix.directory }}" && ./gradlew build

build-python:

strategy:
fail-fast: false
matrix:
python_version: ['3.9', '3.10', '3.11']
os: ['ubuntu-22.04', 'macos-12', 'windows-2022']
project-name: ['ArcadeDrive', 'CANcoder', 'StatusSignals']

runs-on: ${{ matrix.os }}

steps:
- uses: actions/checkout@v4
- uses: actions/setup-python@v4
with:
python-version: ${{ matrix.python_version }}
- name: Install python dependencies
run: |
pip install -U pip
pip install 'robotpy' phoenix6
- name: Test ${{ matrix.project-name }}
run: |
cd "python/${{ matrix.project-name }}" && python3 robot.py test
38 changes: 36 additions & 2 deletions build_parallel_workflow.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@
container: wpilib/roborio-cross-ubuntu:2024-22.04

steps:
- uses: actions/checkout@v3
- uses: actions/checkout@v4

# Grant execute permission for gradlew
- name: Grant execute permission for gradlew
Expand All @@ -40,20 +40,54 @@
# Runs a single command using the runners shell
- name: Compile and run tests on robot code for project ${{{{ matrix.project-name }}}}
run: cd "${{{{ matrix.directory }}}}" && ./gradlew build

build-python:

strategy:
fail-fast: false
matrix:
python_version: ['3.9', '3.10', '3.11']
os: ['ubuntu-22.04', 'macos-12', 'windows-2022']
project-name: [{python_projects}]

runs-on: ${{{{ matrix.os }}}}

steps:
- uses: actions/checkout@v4
- uses: actions/setup-python@v4
with:
python-version: ${{{{ matrix.python_version }}}}
- name: Install python dependencies
run: |
pip install -U pip
pip install 'robotpy' phoenix6
- name: Test ${{{{ matrix.project-name }}}}
run: |
cd "python/${{{{ matrix.project-name }}}}" && python3 robot.py test
"""

PROJECT_MATRIX_TEMPLATE = """
- project-name: '{project_name}'
directory: '{project_dir}'"""

MATRIX_TEMPLATE = "'{project_name}'"

PROJECTS_TO_SEARCH = ["cpp", "java"]
PYTHON_PROJECTS_TO_SEARCH = ["python"]


project_matrix = []
for project_dir in PROJECTS_TO_SEARCH:
# Find every project in here and build up an array of strings to generate the workflow file
for project in os.listdir(project_dir):
project_matrix.append(PROJECT_MATRIX_TEMPLATE.format(project_name=project, project_dir=f"{project_dir}/{project}"))

python_project_matrix = []
for project_dir in PYTHON_PROJECTS_TO_SEARCH:
# Find every project in here and build up an array of strings to generate the workflow file
for project in os.listdir(project_dir):
python_project_matrix.append(MATRIX_TEMPLATE.format(project_name=project))

with open(".github/workflows/build-all-parallel.yml", "w", encoding="utf-8") as workflow_file:
workflow_file.write(WORKFLOW_TEMPLATE.format(projects_as_matrix="".join(project_matrix)))
workflow_file.write(WORKFLOW_TEMPLATE.format(projects_as_matrix="".join(project_matrix),
python_projects=", ".join(python_project_matrix)))
3 changes: 3 additions & 0 deletions python/ArcadeDrive/.deploy_cfg
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
[auth]
hostname = 7762

3 changes: 3 additions & 0 deletions python/ArcadeDrive/.gitignore
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
ctre_sim
__pycache__
.pytest_cache
3 changes: 3 additions & 0 deletions python/ArcadeDrive/.installer_config
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
[auth]
hostname = 7762
CoryNessCTR marked this conversation as resolved.
Show resolved Hide resolved

51 changes: 51 additions & 0 deletions python/ArcadeDrive/robot.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
#!/usr/bin/env python3
"""
This is a demo program for arcade drive in Python with Phoenix 6
"""
import wpilib
from phoenix6 import TalonFX, Follower, DutyCycleOut


class MyRobot(wpilib.TimedRobot):
"""
Example program that shows to do simple arcade drive in robotpy
with Phoenix 6
"""

def robotInit(self):
"""Robot initialization function"""

# Keep a reference to all the motor controllers used
canivore_name = "canivore"
self.front_left_motor = TalonFX(0, canivore_name)
self.rear_left_motor = TalonFX(1, canivore_name)
self.front_right_motor = TalonFX(2, canivore_name)
self.rear_right_motor = TalonFX(3, canivore_name)

# Configure the rear motors to follow the front motors
follow_left_request = Follower(0, False)
self.rear_left_motor.set_control(follow_left_request)

follow_right_request = Follower(2, False)
self.rear_right_motor.set_control(follow_right_request)

# Keep a reference to the DutyCycleOut control request to update periodically
self.left_out = DutyCycleOut(output=0)
self.right_out = DutyCycleOut(output=0)

# Keep a reference to an Xbox Controller for teleop control
self.joy = wpilib.XboxController(0)

def teleopPeriodic(self):
"""Runs the motors with arcade drive"""
# Get throttle and wheel values for arcade drive
throttle = self.joy.getLeftY() * -1
wheel = self.joy.getRightX() * 1

# And set the DutyCycleOut to the motor controllers
self.front_left_motor.set_control(self.left_out.with_output(throttle + wheel))
self.front_right_motor.set_control(self.right_out.with_output(throttle - wheel))


if __name__ == "__main__":
wpilib.run(MyRobot)
6 changes: 6 additions & 0 deletions python/ArcadeDrive/tests/pyfrc_test.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
'''
This test module imports tests that come with pyfrc, and can be used
to test basic functionality of just about any robot.
'''

from pyfrc.tests import *
3 changes: 3 additions & 0 deletions python/CANcoder/.deploy_cfg
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
[auth]
hostname = 7762

3 changes: 3 additions & 0 deletions python/CANcoder/.gitignore
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
ctre_sim
__pycache__
.pytest_cache
3 changes: 3 additions & 0 deletions python/CANcoder/.installer_config
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
[auth]
hostname = 7762

43 changes: 43 additions & 0 deletions python/CANcoder/robot.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
#!/usr/bin/env python3
"""
This is a demo program for CANcoder usage in Phoenix 6
"""
import wpilib
from wpilib import Timer
from phoenix6 import CANcoder

class MyRobot(wpilib.TimedRobot):
"""
Example program that shows how to use CANcoder
in Phoenix 6 python
"""

def robotInit(self):
"""Robot initialization function"""

# Keep a reference to all the motor controllers used
self.cancoder = CANcoder(1, "canivore")

self.timer = Timer()
self.timer.start()

def teleopPeriodic(self):
"""Every 100ms, print the status of the StatusSignal"""

if self.timer.hasElapsed(0.1):
# get_position automatically calls refresh(), no need to manually refresh.
#
# StatusSignals also implement the str dunder to provide a useful print of the signal
pos = self.cancoder.get_position()
print(f"Positions is {str(pos)} with {pos.timestamp.get_latency()} seconds of latency")

# Get the velocity StatusSignal
vel = self.cancoder.get_velocity()
# This time wait for the signal to reduce latency
vel.wait_for_update(0.1)
print(f"Velocity is {vel} with {vel.timestamp.get_latency()} seconds of latency")

print("")

if __name__ == "__main__":
wpilib.run(MyRobot)
31 changes: 31 additions & 0 deletions python/CANcoder/tests/pyfrc_test.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
'''
This test module imports tests that come with pyfrc, and can be used
to test basic functionality of just about any robot.
'''

from pyfrc.tests import *
from phoenix6 import CANcoder, CANcoderConfiguration

FIRST_SET = 0
SECOND_SET = 4.8

def assert_almost_equal(a: float, b: float, range_val: float):
"""
Assert that a is within range of b
"""
assert a >= (b - range_val) and a <= (b + range_val)

def test_pos_setter():
cancoder = CANcoder(1, "sim")
pos = cancoder.get_position()

cfg = CANcoderConfiguration()
cancoder.configurator.apply(cfg)

cancoder.set_position(FIRST_SET)
pos.wait_for_update(1.0)
assert_almost_equal(pos.value, FIRST_SET, 0.01)

cancoder.set_position(SECOND_SET)
pos.wait_for_update(1.0)
assert_almost_equal(pos.value, SECOND_SET, 0.01)
3 changes: 3 additions & 0 deletions python/PositionClosedLoop/.deploy_cfg
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
[auth]
hostname = 7762

3 changes: 3 additions & 0 deletions python/PositionClosedLoop/.gitignore
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
ctre_sim
__pycache__
.pytest_cache
3 changes: 3 additions & 0 deletions python/PositionClosedLoop/.installer_config
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
[auth]
hostname = 7762

55 changes: 55 additions & 0 deletions python/PositionClosedLoop/robot.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,55 @@
#!/usr/bin/env python3
"""
This is a demo program for TalonFX Position PID usage in Phoenix 6
"""
import wpilib
from wpilib import Timer, XboxController
from phoenix6 import TalonFX, TalonFXConfiguration, PositionVoltage

class MyRobot(wpilib.TimedRobot):
"""
Example program that shows how to use TalonFX
in Phoenix 6 python
"""

def robotInit(self):
"""Robot initialization function"""

# Keep a reference to all the motor controllers used
self.talonfx = TalonFX(1, "canivore")
self.position_request = PositionVoltage(0)

cfg = TalonFXConfiguration()
# Set PID gains
cfg.slot0.k_p = 10
cfg.slot0.k_d = 0.2

# Apply PID gains to motor
self.talonfx.configurator.apply(cfg)

self.joystick = XboxController(0)
self.timer = Timer()
self.timer.start()

def teleopInit(self):
"""Set the position of the talonfx to 0 so we know we're centered"""
self.talonfx.set_position(0)

def teleopPeriodic(self):
"""Every 100ms, print the status of the StatusSignal"""

# Target a position of +- 10 rotations depending on joystick position
self.talonfx.set_control(self.position_request.with_position(self.joystick.getLeftY() * 10))

if self.timer.hasElapsed(0.1):
# Print the position & velocity to see what they are
pos = self.talonfx.get_position()
vel = self.talonfx.get_velocity()

print(f"Position: {pos}")
print(f"Velocity: {vel}")

print("")

if __name__ == "__main__":
wpilib.run(MyRobot)
63 changes: 63 additions & 0 deletions python/PositionClosedLoop/tests/pyfrc_test.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,63 @@
'''
This test module imports tests that come with pyfrc, and can be used
to test basic functionality of just about any robot.
'''

from time import sleep
from pyfrc.tests import *
from phoenix6 import TalonFX, TalonFXConfiguration, PositionVoltage
from phoenix6.unmanaged import feed_enable
from wpilib.simulation import DCMotorSim
from wpimath.system.plant import DCMotor
from wpimath.units import radiansToRotations

FIRST_SET = 0
SECOND_SET = 4.8

def assert_almost_equal(a: float, b: float, range_val: float):
"""
Assert that a is within range of b
"""
assert a >= (b - range_val) and a <= (b + range_val)

# PID loop means we should be kinda fast, let's target 10ms
LOOP_PERIOD = 0.01
def wait_with_sim(time: float, fx: TalonFX, dcmotorsim: DCMotorSim):
start_time = 0
while start_time < time:
feed_enable(LOOP_PERIOD * 2)
start_time += LOOP_PERIOD

dcmotorsim.setInputVoltage(fx.sim_state.motor_voltage)
dcmotorsim.update(LOOP_PERIOD)
fx.sim_state.set_raw_rotor_position(radiansToRotations(dcmotorsim.getAngularPosition()))
fx.sim_state.set_rotor_velocity(radiansToRotations(dcmotorsim.getAngularVelocity()))

sleep(LOOP_PERIOD)

def test_position_closed_loop():
talonfx = TalonFX(1, "sim")
motorsim = DCMotorSim(DCMotor.falcon500FOC(1), 1.0, 0.001)
pos = talonfx.get_position()

talonfx.sim_state.set_raw_rotor_position(radiansToRotations(motorsim.getAngularPosition()))
talonfx.sim_state.set_supply_voltage(12)

cfg = TalonFXConfiguration()
cfg.slot0.k_p = 2
cfg.slot0.k_d = 0.1
assert talonfx.configurator.apply(cfg).is_ok()
assert talonfx.set_position(FIRST_SET).is_ok()

pos.wait_for_update(1)
assert_almost_equal(pos.value, 0, 0.01)

# Closed loop for 1 seconds to a target of 1 rotation, and verify we're close
target_control = PositionVoltage(position=1.0)
talonfx.set_control(target_control)

wait_with_sim(1, talonfx, motorsim)

# Verify position is close to target
pos.wait_for_update(1)
assert_almost_equal(pos.value, 1, 0.01)
3 changes: 3 additions & 0 deletions python/StatusSignals/.deploy_cfg
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
[auth]
hostname = 7762

Loading