Skip to content

Commit c5de10f

Browse files
Tyler-DuckworthTyler Duckworth
and
Tyler Duckworth
authored
Add non-PWM examples (#22)
* init * added black formatting * fixed errors * Fixed errors and added black formatting * Uncommented lines that led to erroneous testing * Tweaked velocity-pid example * Added can-tank-drive example * Fixed SmartDashboard configuration * Fixed testing environment configuration. * Removed unnecessary imports * Removed unnecessary imports * Fixed enum changes in get-set-params * Reformatted get-set-params to pass black CI check Co-authored-by: Tyler Duckworth <[email protected]>
1 parent d6fa931 commit c5de10f

File tree

10 files changed

+808
-0
lines changed

10 files changed

+808
-0
lines changed

Diff for: examples/can-arcade-drive/robot.py

+63
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,63 @@
1+
# ----------------------------------------------------------------------------
2+
# Copyright (c) 2017-2018 FIRST. All Rights Reserved.
3+
# Open Source Software - may be modified and shared by FRC teams. The code
4+
# must be accompanied by the FIRST BSD license file in the root directory of
5+
# the project.
6+
# ----------------------------------------------------------------------------
7+
8+
import rev
9+
import wpilib
10+
from wpilib.drive import DifferentialDrive
11+
12+
13+
class Robot(wpilib.TimedRobot):
14+
def robotInit(self):
15+
# SPARK MAX controllers are intialized over CAN by constructing a
16+
# CANSparkMax object
17+
#
18+
# The CAN ID, which can be configured using the SPARK MAX Client, is passed
19+
# as the first parameter
20+
#
21+
# The motor type is passed as the second parameter.
22+
# Motor type can either be:
23+
# rev.MotorType.kBrushless
24+
# rev.MotorType.kBrushed
25+
#
26+
# The example below initializes four brushless motors with CAN IDs
27+
# 1, 2, 3, 4. Change these parameters to match your setup
28+
self.leftLeadMotor = rev.CANSparkMax(1, rev.MotorType.kBrushless)
29+
self.rightLeadMotor = rev.CANSparkMax(3, rev.MotorType.kBrushless)
30+
self.leftFollowMotor = rev.CANSparkMax(2, rev.MotorType.kBrushless)
31+
self.rightFollowMotor = rev.CANSparkMax(4, rev.MotorType.kBrushless)
32+
33+
# Passing in the lead motors into DifferentialDrive allows any
34+
# commmands sent to the lead motors to be sent to the follower motors.
35+
self.driveTrain = DifferentialDrive(self.leftLeadMotor, self.rightLeadMotor)
36+
self.joystick = wpilib.Joystick(0)
37+
38+
# The RestoreFactoryDefaults method can be used to reset the
39+
# configuration parameters in the SPARK MAX to their factory default
40+
# state. If no argument is passed, these parameters will not persist
41+
# between power cycles
42+
self.leftLeadMotor.restoreFactoryDefaults()
43+
self.rightLeadMotor.restoreFactoryDefaults()
44+
self.leftFollowMotor.restoreFactoryDefaults()
45+
self.rightFollowMotor.restoreFactoryDefaults()
46+
47+
# In CAN mode, one SPARK MAX can be configured to follow another. This
48+
# is done by calling the follow() method on the SPARK MAX you want to
49+
# configure as a follower, and by passing as a parameter the SPARK MAX
50+
# you want to configure as a leader.
51+
#
52+
# This is shown in the example below, where one motor on each side of
53+
# our drive train is configured to follow a lead motor.
54+
self.leftFollowMotor.follow(self.leftLeadMotor)
55+
self.rightFollowMotor.follow(self.rightLeadMotor)
56+
57+
def teleopPeriodic(self):
58+
# Drive with arcade style
59+
self.driveTrain.arcadeDrive(-self.joystick.getY(), self.joystick.getX())
60+
61+
62+
if __name__ == "__main__":
63+
wpilib.run(Robot)

Diff for: examples/can-tank-drive/robot.py

+48
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,48 @@
1+
# ----------------------------------------------------------------------------
2+
# Copyright (c) 2017-2018 FIRST. All Rights Reserved.
3+
# Open Source Software - may be modified and shared by FRC teams. The code
4+
# must be accompanied by the FIRST BSD license file in the root directory of
5+
# the project.
6+
# ----------------------------------------------------------------------------
7+
8+
import rev
9+
import wpilib
10+
from wpilib.drive import DifferentialDrive
11+
12+
13+
class Robot(wpilib.TimedRobot):
14+
def robotInit(self):
15+
# SPARK MAX controllers are intialized over CAN by constructing a
16+
# CANSparkMax object
17+
#
18+
# The CAN ID, which can be configured using the SPARK MAX Client, is passed
19+
# as the first parameter
20+
#
21+
# The motor type is passed as the second parameter.
22+
# Motor type can either be:
23+
# rev.MotorType.kBrushless
24+
# rev.MotorType.kBrushed
25+
#
26+
# The example below initializes two brushless motors with CAN IDs
27+
# 1 and 2. Change these parameters to match your setup
28+
self.leftMotor = rev.CANSparkMax(1, rev.MotorType.kBrushless)
29+
self.rightMotor = rev.CANSparkMax(2, rev.MotorType.kBrushless)
30+
31+
# The RestoreFactoryDefaults method can be used to reset the
32+
# configuration parameters in the SPARK MAX to their factory default
33+
# state. If no argument is passed, these parameters will not persist
34+
# between power cycles
35+
self.leftMotor.restoreFactoryDefaults()
36+
self.rightMotor.restoreFactoryDefaults()
37+
38+
self.driveTrain = DifferentialDrive(self.leftMotor, self.rightMotor)
39+
self.l_stick = wpilib.Joystick(0)
40+
self.r_stick = wpilib.Joystick(1)
41+
42+
def teleopPeriodic(self):
43+
# Create tank drive
44+
self.driveTrain.tankDrive(self.l_stick.getY(), self.r_stick.getY())
45+
46+
47+
if __name__ == "__main__":
48+
wpilib.run(Robot)

Diff for: examples/get-set-params/robot.py

+63
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,63 @@
1+
# ----------------------------------------------------------------------------
2+
# Copyright (c) 2017-2018 FIRST. All Rights Reserved.
3+
# Open Source Software - may be modified and shared by FRC teams. The code
4+
# must be accompanied by the FIRST BSD license file in the root directory of
5+
# the project.
6+
# ----------------------------------------------------------------------------
7+
8+
import rev
9+
import wpilib
10+
11+
12+
class Robot(wpilib.TimedRobot):
13+
def robotInit(self):
14+
# Create motor
15+
self.motor = rev.CANSparkMax(1, rev.MotorType.kBrushless)
16+
17+
self.joystick = wpilib.Joystick(0)
18+
19+
# The restoreFactoryDefaults method can be used to reset the
20+
# configuration parameters in the SPARK MAX to their factory default
21+
# state. If no argument is passed, these parameters will not persist
22+
# between power cycles
23+
self.motor.restoreFactoryDefaults()
24+
25+
# Parameters can be set by calling the appropriate set() method on the
26+
# CANSparkMax object whose properties you want to change
27+
#
28+
# Set methods will return one of three CANError values which will let
29+
# you know if the parameter was successfully set:
30+
# CANError.kOk
31+
# CANError.kError
32+
# CANError.kTimeout
33+
if self.motor.setIdleMode(rev.IdleMode.kCoast) is not rev.CANError.kOk:
34+
wpilib.SmartDashboard.putString("Idle Mode", "Error")
35+
36+
# Similarly, parameters will have a get() method which allows you to
37+
# retrieve their values from the controller
38+
if self.motor.getIdleMode() is rev.IdleMode.kCoast:
39+
wpilib.SmartDashboard.putString("Idle Mode", "Coast")
40+
else:
41+
wpilib.SmartDashboard.putString("Idle Mode", "Brake")
42+
43+
# Set ramp rate to 0
44+
if self.motor.setOpenLoopRampRate(0) is not rev.CANError.kOk:
45+
wpilib.SmartDashboard.putString("Ramp Rate", "Error")
46+
47+
# Read back ramp value
48+
wpilib.SmartDashboard.putString(
49+
"Ramp Rate", str(self.motor.getOpenLoopRampRate())
50+
)
51+
52+
def teleopPeriodic(self):
53+
# Pair motor and the joystick's Y Axis
54+
self.motor.set(self.joystick.getY())
55+
56+
# Put Voltage, Temperature, and Motor Output onto SmartDashboard
57+
wpilib.SmartDashboard.putNumber("Voltage", self.motor.getBusVoltage())
58+
wpilib.SmartDashboard.putNumber("Temperature", self.motor.getMotorTemperature())
59+
wpilib.SmartDashboard.putNumber("Output", self.motor.getAppliedOutput())
60+
61+
62+
if __name__ == "__main__":
63+
wpilib.run(Robot)

Diff for: examples/limit-switch/robot.py

+76
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,76 @@
1+
# ----------------------------------------------------------------------------
2+
# Copyright (c) 2017-2018 FIRST. All Rights Reserved.
3+
# Open Source Software - may be modified and shared by FRC teams. The code
4+
# must be accompanied by the FIRST BSD license file in the root directory of
5+
# the project.
6+
# ----------------------------------------------------------------------------
7+
8+
import rev
9+
import wpilib
10+
11+
# Before Running:
12+
# Open Shuffleboard, select File->Load Layout and select the
13+
# shuffleboard.json that is in the root directory of this example
14+
15+
16+
class Robot(wpilib.TimedRobot):
17+
def robotInit(self):
18+
# Create motor
19+
self.motor = rev.CANSparkMax(1, rev.MotorType.kBrushless)
20+
21+
self.joystick = wpilib.Joystick(0)
22+
23+
# A CANDigitalInput object is constructed using the
24+
# GetForwardLimitSwitch() or
25+
# GetReverseLimitSwitch() method on an existing CANSparkMax object,
26+
# depending on which direction you would like to limit
27+
#
28+
# Limit switches can be configured to one of two polarities:
29+
# rev.CANDigitalInput.LimitSwitchPolarity.kNormallyOpen
30+
# rev.CANDigitalInput.LimitSwitchPolarity.kNormallyClosed
31+
self.forwardLimit = self.motor.getForwardLimitSwitch(
32+
rev.LimitSwitchPolarity.kNormallyClosed
33+
)
34+
self.reverseLimit = self.motor.getReverseLimitSwitch(
35+
rev.LimitSwitchPolarity.kNormallyClosed
36+
)
37+
38+
self.forwardLimit.enableLimitSwitch(False)
39+
self.reverseLimit.enableLimitSwitch(False)
40+
41+
wpilib.SmartDashboard.putBoolean(
42+
"Forward Limit Enabled", self.forwardLimit.isLimitSwitchEnabled()
43+
)
44+
wpilib.SmartDashboard.putBoolean(
45+
"Reverse Limit Enabled", self.forwardLimit.isLimitSwitchEnabled()
46+
)
47+
48+
def teleopPeriodic(self):
49+
# Pair motor and the joystick's Y Axis
50+
self.motor.set(self.joystick.getY())
51+
52+
# enable/disable limit switches based on value read from SmartDashboard
53+
self.forwardLimit.enableLimitSwitch(
54+
wpilib.SmartDashboard.getBoolean("Forward Limit Enabled", False)
55+
)
56+
self.reverseLimit.enableLimitSwitch(
57+
wpilib.SmartDashboard.getBoolean("Reverse Limit Enabled", False)
58+
)
59+
60+
# The get() method can be used on a CANDigitalInput object to read the
61+
# state of the switch.
62+
#
63+
# In this example, the polarity of the switches are set to normally
64+
# closed. In this case, get() will return true if the switch is
65+
# pressed. It will also return true if you do not have a switch
66+
# connected. get() will return false when the switch is released.
67+
wpilib.SmartDashboard.putBoolean(
68+
"Forward Limit Switch", self.forwardLimit.get()
69+
)
70+
wpilib.SmartDashboard.putBoolean(
71+
"Reverse Limit Switch", self.reverseLimit.get()
72+
)
73+
74+
75+
if __name__ == "__main__":
76+
wpilib.run(Robot)

Diff for: examples/limit-switch/shuffleboard.json

+72
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,72 @@
1+
{
2+
"tabPane": [
3+
{
4+
"title": "SmartDashboard",
5+
"autoPopulate": true,
6+
"autoPopulatePrefix": "SmartDashboard/",
7+
"widgetPane": {
8+
"gridSize": 128.0,
9+
"showGrid": true,
10+
"hgap": 16.0,
11+
"vgap": 16.0,
12+
"tiles": {
13+
"0,0": {
14+
"size": [
15+
2,
16+
3
17+
],
18+
"content": {
19+
"_type": "List Layout",
20+
"_title": "Limit Switch",
21+
"Layout/Label position": "BOTTOM",
22+
"_children": [
23+
{
24+
"_type": "Toggle Switch",
25+
"_source0": "network_table:///SmartDashboard/Forward Limit Enabled",
26+
"_title": "Forward Limit Enabled"
27+
},
28+
{
29+
"_type": "Toggle Switch",
30+
"_source0": "network_table:///SmartDashboard/Reverse Limit Enabled",
31+
"_title": "Reverse Limit Enabled"
32+
},
33+
{
34+
"_type": "Boolean Box",
35+
"_source0": "network_table:///SmartDashboard/Forward Limit Switch",
36+
"_title": "Forward Limit Switch",
37+
"Colors/Color when true": "#7CFC00FF",
38+
"Colors/Color when false": "#8B0000FF"
39+
},
40+
{
41+
"_type": "Boolean Box",
42+
"_source0": "network_table:///SmartDashboard/Reverse Limit Switch",
43+
"_title": "Reverse Limit Switch",
44+
"Colors/Color when true": "#7CFC00FF",
45+
"Colors/Color when false": "#8B0000FF"
46+
}
47+
]
48+
}
49+
}
50+
}
51+
}
52+
},
53+
{
54+
"title": "LiveWindow",
55+
"autoPopulate": true,
56+
"autoPopulatePrefix": "LiveWindow/",
57+
"widgetPane": {
58+
"gridSize": 128.0,
59+
"showGrid": true,
60+
"hgap": 16.0,
61+
"vgap": 16.0,
62+
"tiles": {}
63+
}
64+
}
65+
],
66+
"windowGeometry": {
67+
"x": -1640.0,
68+
"y": 54.0,
69+
"width": 1540.0,
70+
"height": 832.0
71+
}
72+
}

0 commit comments

Comments
 (0)