Skip to content

Commit

Permalink
Merge pull request #55 from robotpy/update-5.3.1.0
Browse files Browse the repository at this point in the history
Upgrade to Phoenix 5.3.1.0
  • Loading branch information
virtuald committed Apr 1, 2018
2 parents 1cb54ee + 8e36d50 commit 5178d14
Show file tree
Hide file tree
Showing 13 changed files with 288 additions and 82 deletions.
2 changes: 1 addition & 1 deletion .gittrack
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
[git-source-track]
validation_root = ctre
upstream_root = ../Phoenix-frc-lib/
upstream_commit = 9704468db863a6e12d38feb60ba01f0cb050de49
upstream_commit = 666d176a08151793044ab74e0005f13d3732ed96

66 changes: 26 additions & 40 deletions ctre/_impl/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,49 +12,35 @@
from .autogen.canifier_sim import CANifier
from .autogen.motcontroller_sim import MotController
from .autogen.pigeonimu_sim import PigeonIMU
from .autogen.ctre_sim_enums import (
ControlMode,
ErrorCode,
NeutralMode,
RemoteFeedbackDevice,
FeedbackDevice,
StatusFrame,
StatusFrameEnhanced,
VelocityMeasPeriod,
RemoteLimitSwitchSource,
LimitSwitchNormal,
LimitSwitchSource,
ParamEnum,
CANifierStatusFrame,
CANifierControlFrame,
GeneralPin,
PigeonIMU_StatusFrame,
PigeonIMU_ControlFrame,
TrajectoryDuration,
)
from .autogen import ctre_sim_enums as _enum_module
else:
from .ctre_roborio import (
CANifier,
MotController,
PigeonIMU
)
from .ctre_roborio import (
ControlMode,
ErrorCode,
NeutralMode,
RemoteFeedbackDevice,
FeedbackDevice,
StatusFrame,
StatusFrameEnhanced,
VelocityMeasPeriod,
RemoteLimitSwitchSource,
LimitSwitchNormal,
LimitSwitchSource,
ParamEnum,
CANifierStatusFrame,
CANifierControlFrame,
GeneralPin,
PigeonIMU_StatusFrame,
PigeonIMU_ControlFrame,
TrajectoryDuration,
)
from . import ctre_roborio as _enum_module

# enums
ControlMode = _enum_module.ControlMode
DemandType = _enum_module.DemandType
ErrorCode = _enum_module.ErrorCode
NeutralMode = _enum_module.NeutralMode
RemoteFeedbackDevice = _enum_module.RemoteFeedbackDevice
FeedbackDevice = _enum_module.FeedbackDevice
FollowerType = _enum_module.FollowerType
StatusFrame = _enum_module.StatusFrame
StatusFrameEnhanced = _enum_module.StatusFrameEnhanced
VelocityMeasPeriod = _enum_module.VelocityMeasPeriod
RemoteLimitSwitchSource = _enum_module.RemoteLimitSwitchSource
LimitSwitchNormal = _enum_module.LimitSwitchNormal
LimitSwitchSource = _enum_module.LimitSwitchSource
ParamEnum = _enum_module.ParamEnum
CANifierStatusFrame = _enum_module.CANifierStatusFrame
CANifierControlFrame = _enum_module.CANifierControlFrame
GeneralPin = _enum_module.GeneralPin
PigeonIMU_StatusFrame = _enum_module.PigeonIMU_StatusFrame
PigeonIMU_ControlFrame = _enum_module.PigeonIMU_ControlFrame
TrajectoryDuration = _enum_module.TrajectoryDuration

del _enum_module
2 changes: 2 additions & 0 deletions ctre/_impl/ctre_roborio.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,9 @@ typedef py::call_guard<py::gil_scoped_release> release_gil;

#include "ctre/phoenix/MotorControl/ControlFrame.h"
#include "ctre/phoenix/MotorControl/ControlMode.h"
#include "ctre/phoenix/MotorControl/DemandType.h"
#include "ctre/phoenix/MotorControl/FeedbackDevice.h"
#include "ctre/phoenix/MotorControl/FollowerType.h"
#include "ctre/phoenix/MotorControl/LimitSwitchType.h"
#include "ctre/phoenix/MotorControl/NeutralMode.h"
#include "ctre/phoenix/MotorControl/RemoteSensorSource.h"
Expand Down
101 changes: 84 additions & 17 deletions ctre/basemotorcontroller.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# validated: 2018-01-14 DV f0e94123427a java/src/com/ctre/phoenix/motorcontrol/can/BaseMotorController.java
# validated: 2018-03-01 DS e8221da18ba9 java/src/com/ctre/phoenix/motorcontrol/can/BaseMotorController.java
#----------------------------------------------------------------------------
#  Software License Agreement
#
Expand Down Expand Up @@ -27,6 +27,9 @@
from ._impl import (
MotController,
ControlMode,
ErrorCode,
DemandType,
FollowerType,
NeutralMode,
VelocityMeasPeriod,
LimitSwitchNormal,
Expand All @@ -44,6 +47,7 @@ class BaseMotorController(MotController):
"""Base motor controller features for all CTRE CAN motor controllers."""

ControlMode = ControlMode
DemandType = DemandType
LimitSwitchNormal = LimitSwitchNormal
NeutralMode = NeutralMode
ParamEnum = ParamEnum
Expand Down Expand Up @@ -71,15 +75,17 @@ def getDeviceID(self):
:returns: Device number.
"""
return self.getDeviceNumber()

__set4_modes = {ControlMode.Velocity, ControlMode.Position, ControlMode.MotionMagic, ControlMode.MotionProfile, ControlMode.MotionProfileArc}

def set(self, mode: ControlMode, demand0: float, demand1: float = 0.0):
def set(self, mode: ControlMode, demand0: float, demand1Type: DemandType = DemandType.Neutral, demand1: float = 0.0):
"""
Sets the appropriate output on the talon, depending on the mode.
:param mode:
The output mode to apply.
:param demand0:
The output value to apply. such as advanced feed forward and/or cascaded close-looping in firmware.
The output value to apply. such as advanced feed forward and/or auxiliary close-looping in firmware.
In :attr:`.ControlMode.PercentOutput`, the output is between -1.0 and 1.0, with 0.0 as
stopped.
Expand All @@ -93,18 +99,40 @@ def set(self, mode: ControlMode, demand0: float, demand1: float = 0.0):
In :attr:`.ControlMode.Position` mode, output value is in encoder ticks or an analog value, depending on the sensor.
In :attr:`.ControlMode.Follower` mode, the output value is the integer device ID of the talon to duplicate.
:type demand0: float
:param demand1Type:
The demand type for demand1.
* Neutral: Ignore demand1 and apply no change to the demand0 output.
* AuxPID: Use demand1 to set the target for the auxiliary PID 1.
* ArbitraryFeedForward: Use demand1 as an arbitrary additive value to the
demand0 output. In PercentOutput the demand0 output is the motor output,
and in closed-loop modes the demand0 output is the output of PID0.
:param demand1:
Supplemental value. This will also be control mode specific for future features.
:type demand1: float
see :meth:`.selectProfileSlot` to choose between the two sets of gains.
Arcade Drive Example::
_talonLeft.set(ControlMode.PercentOutput, joyForward, DemandType.ArbitraryFeedForward, +joyTurn)
_talonRght.set(ControlMode.PercentOutput, joyForward, DemandType.ArbitraryFeedForward, -joyTurn)
Drive Straight Example::
# Note: Selected Sensor Configuration is necessary for both PID0 and PID1.
_talonLeft.follow(_talonRght, FollowerType.AuxOutput1)
_talonRght.set(ControlMode.PercentOutput, joyForward, DemandType.AuxPID, desiredRobotHeading)
Drive Straight to a Distance Example::
# Note: Other configurations (sensor selection, PID gains, etc.) need to be set.
_talonLeft.follow(_talonRght, FollowerType.AuxOutput1);
_talonRght.set(ControlMode.MotionMagic, targetDistance, DemandType.AuxPID, desiredRobotHeading)
"""
self.controlMode = mode
self.sendMode = mode

if self.controlMode == ControlMode.PercentOutput:
self.setDemand(self.sendMode, int(1023 * demand0), 0)
self._set_4(self.sendMode, demand0, demand1, demand1Type)
elif self.controlMode == ControlMode.Follower:
# did caller specify device ID
if 0 <= demand0 <= 62:
Expand All @@ -114,9 +142,9 @@ def set(self, mode: ControlMode, demand0: float, demand1: float = 0.0):
work |= int(demand0) & 0xFF
else:
work = int(demand0)
self.setDemand(self.sendMode, work, 0)
elif self.controlMode in [ControlMode.Velocity, ControlMode.Position, ControlMode.MotionMagic, ControlMode.MotionMagicArc, ControlMode.MotionProfile]:
self.setDemand(self.sendMode, int(demand0), 0)
self._set_4(self.sendMode, work, demand1, demand1Type)
elif self.controlMode in self.__set4_modes:
self._set_4(self.sendMode, demand0, demand1, demand1Type)
elif self.controlMode == ControlMode.Current:
self.setDemand(self.sendMode, int(1000. * demand0), 0) # milliamps
else:
Expand Down Expand Up @@ -173,9 +201,13 @@ def pushMotionProfileTrajectory(self, trajPt: TrajectoryPoint):
position: servo position in sensor units.
velocity: velocity to feed-forward in sensor units per 100ms.
profileSlotSelect: which slot to pull PIDF gains from. Currently
supports 0,1,2,3.
profileSlotSelect0: Which slot to get PIDF gains. PID is used for position servo. F is used
as the Kv constant for velocity feed-forward. Typically this is hardcoded
to the a particular slot, but you are free gain schedule if need be.
Choose from [0,3]
profileSlotSelect1: Which slot to get PIDF gains for auxiliary PId.
This only has impact during MotionProfileArc Control mode.
Choose from [0,1].
isLastPoint: set to nonzero to signal motor controller to keep processing this
trajectory point, instead of jumping to the next one
when timeDurMs expires. Otherwise MP executer will
Expand All @@ -188,11 +220,15 @@ def pushMotionProfileTrajectory(self, trajPt: TrajectoryPoint):
Typically the first point should have this set only thus
allowing the remainder of the MP positions to be relative to
zero.
timeDur: Duration to apply this trajectory pt.
This time unit is ADDED to the exising base time set by
configMotionProfileTrajectoryPeriod().
:returns: CTR_OKAY if trajectory point push ok. ErrorCode if buffer is
full due to kMotionProfileTopBufferCapacity.
"""
return super()._pushMotionProfileTrajectory_2(
trajPt.position, trajPt.velocity, trajPt.headingDeg,
trajPt.position, trajPt.velocity, trajPt.auxiliaryPos,
trajPt.profileSlotSelect0, trajPt.profileSlotSelect1,
trajPt.isLastPoint, trajPt.zeroPos, trajPt.timeDur
)
Expand All @@ -219,7 +255,7 @@ def getStickyFaults(self) -> typing.Tuple[int, StickyFaults]:
def getBaseID(self) -> int:
return self.arbId

def follow(self, masterToFollow: 'BaseMotorController'):
def follow(self, masterToFollow: 'BaseMotorController', followerType: FollowerType = FollowerType.PercentOutput):
"""
Set the control mode and output value so that this motor controller will
follow another motor controller. Currently supports following Victor SPX
Expand All @@ -231,7 +267,15 @@ def follow(self, masterToFollow: 'BaseMotorController'):
id24 = id24 & 0xFFFF
id24 <<= 8
id24 |= (id32 & 0xFF)
self.set(ControlMode.Follower, id24)

if followerType == FollowerType.PercentOutput:
self.set(ControlMode.Follower, id24)
elif followerType == FollowerType.AuxOutput1:
# follow the motor controller, but set the aux flag
# to ensure we follow the processed output
self.set(ControlMode.Follower, id24, DemandType.AuxPID, 0)
else:
self.neutralOutput()

def valueUpdated(self):
"""
Expand All @@ -247,3 +291,26 @@ def getControlMode(self) -> ControlMode:
"""
:returns: control mode motor controller is in"""
return self.controlMode

def configAuxPIDPolarity(self, invert: bool, timeoutMs: int) -> ErrorCode:
"""Configures the Polarity of the Auxiliary PID (PID1).
Standard Polarity:
* Primary Output = PID0 + PID1
* Auxiliary Output = PID0 - PID1
Inverted Polarity:
* Primary Output = PID0 - PID1
* Auxiliary Output = PID0 + PID1
:param invert: If true, use inverted PID1 output polarity.
:param timeoutMs: Timeout value in ms. If nonzero, function will wait for config
success and report an error if it times out. If zero, no
blocking or checking is performed.
:returns: Error Code
"""
return self.configSetParameter(ParamEnum.ePIDLoopPolarity, 1 if invert else 0, 0, 1, timeoutMs)
7 changes: 6 additions & 1 deletion ctre/canifier.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# validated: 2018-01-05 EN 8f8595a20145 java/src/com/ctre/phoenix/CANifier.java
# validated: 2018-03-01 DS a3eae14b229d java/src/com/ctre/phoenix/CANifier.java
#----------------------------------------------------------------------------
#  Software License Agreement
#
Expand Down Expand Up @@ -91,6 +91,7 @@ def __init__(self, deviceId: int):
"""
super().__init__()
self._create1(deviceId)
self._deviceNumber = deviceId
# python-specific: tempPins not needed
hal.report(hal.UsageReporting.kResourceType_CANifier, deviceId + 1)

Expand Down Expand Up @@ -178,3 +179,7 @@ def getStickyFaults(self, toFill: CANifierStickyFaults):
_, bits = super().getStickyFaults()
toFill.update(bits)
return self.getLastError()

def getDeviceID(self):
""":returns: The Device Number"""
return self._deviceNumber
8 changes: 6 additions & 2 deletions ctre/pigeonimu.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# validated: 2018-01-14 DV 2a1c9b5fb45b java/src/com/ctre/phoenix/sensors/PigeonIMU.java
# validated: 2018-03-01 DS a3eae14b229d java/src/com/ctre/phoenix/sensors/PigeonIMU.java
#----------------------------------------------------------------------------
#  Software License Agreement
#
Expand Down Expand Up @@ -209,7 +209,7 @@ def __init__(self, *args, **kwargs):
deviceNumber_arg = ("deviceNumber", [int])
talonSrx_arg = ("talonSrx", [TalonSRX])
templates = [[deviceNumber_arg], [talonSrx_arg]]
index, results = match_arglist('PIDController.__init__',
index, results = match_arglist('PigeonIMU.__init__',
args, kwargs, templates)
self.generalStatus = [0] * 10
self.fusionStatus = [0] * 10
Expand Down Expand Up @@ -262,3 +262,7 @@ def getStickyFaults(self) -> typing.Tuple[int, PigeonIMU_StickyFaults]:
"""
_, bits = super().getStickyFaults()
return self.getLastError(), PigeonIMU_StickyFaults(bits)

def getDeviceID(self):
""":returns: The Device Number"""
return self._deviceNumber
8 changes: 4 additions & 4 deletions ctre/trajectorypoint.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# validated: 2018-01-14 DV 76dd48fe2e6a libraries/driver/include/ctre/phoenix/Motion/TrajectoryPoint.h
# validated: 2018-03-01 DS b3d643236ddc libraries/driver/include/ctre/phoenix/Motion/TrajectoryPoint.h
from collections import namedtuple

from ._impl import TrajectoryDuration
Expand All @@ -8,12 +8,12 @@

#: Motion Profile Trajectory Point.
#: This is simply a data transfer object.
TrajectoryPoint = namedtuple("TrajectoryPoint", ["position", "velocity", "headingDeg", "profileSlotSelect0",
TrajectoryPoint = namedtuple("TrajectoryPoint", ["position", "velocity", "auxiliaryPos", "profileSlotSelect0",
"profileSlotSelect1", "isLastPoint", "zeroPos", "timeDur"])
TrajectoryPoint.TrajectoryDuration = TrajectoryDuration
TrajectoryPoint.position.__doc__ = "The position to servo to."
TrajectoryPoint.velocity.__doc__ = "The velocity to feed-forward."
#TrajectoryPoint.headingDeg.__doc__ = ""
TrajectoryPoint.auxiliaryPos.__doc__ = "The position for auxiliary PID to target."
TrajectoryPoint.profileSlotSelect0.__doc__ = """
Which slot to get PIDF gains.
PID is used for position servo.
Expand All @@ -23,7 +23,7 @@
Choose from [0,3]
"""
TrajectoryPoint.profileSlotSelect1.__doc__ = """
Which slot to get PIDF gains for cascaded PID.
Which slot to get PIDF gains for auxiliary PID.
This only has impact during MotionProfileArc Control mode.
Choose from [0,1]
"""
Expand Down
2 changes: 1 addition & 1 deletion ctre/wpi_talonsrx.py
Original file line number Diff line number Diff line change
Expand Up @@ -104,7 +104,7 @@ def set(self, *args, **kwargs):

self.speed = 0.0
if index == 2:
super().set(results['mode'], results['demand0'], results['demand1'])
super().set(results['mode'], results['demand0'], demand1=results['demand1'])
else:
if index == 0:
self.speed = value = results['speed']
Expand Down

0 comments on commit 5178d14

Please sign in to comment.