Skip to content

Commit

Permalink
Merge pull request #7 from Twinters007/MotionMagic
Browse files Browse the repository at this point in the history
Add Motion Magic example. Update sim files to include params
  • Loading branch information
virtuald committed May 6, 2017
2 parents e38f496 + 95be7d3 commit 893347b
Show file tree
Hide file tree
Showing 4 changed files with 159 additions and 14 deletions.
73 changes: 60 additions & 13 deletions ctre/_impl/cantalon_sim.py
Original file line number Diff line number Diff line change
Expand Up @@ -116,7 +116,35 @@ class param_t(Enum):
eMotionProfileHasUnderrunErr = 119
eReserved120 = 120
eLegacyControlMode = 121


eMotMag_Accel = 122
eMotMag_VelCruise = 123
eStatus10FrameRate = 124 # TALON_Status_10_MotMag_100ms_t
eCurrentLimThreshold = 125

eBldcStatus1FrameRate = 129 # CYCLONE_BLDC_Status_1_BTC_MEC
eBldcStatus2FrameRate = 130 # CYCLONE_BLDC_Status_2_SLC
eBldcStatus3FrameRate = 131 # CYCLONE_BLDC_Status_3_SLD


eCustomParam0 = 137
eCustomParam1 = 138
ePersStorageSaving = 139

eClearPositionOnLimitF = 144
eClearPositionOnLimitR = 145
eNominalBatteryVoltage = 146
eSampleVelocityPeriod = 147
eSampleVelocityWindow = 148

eMotionMeas_YawOffset = 160
eMotionMeas_CompassOffset = 161
eMotionMeas_BetaGain = 162
eMotionMeas_Reserved163 = 163
eMotionMeas_GyroNoMotionCal = 164
eMotionMeas_EnterCalibration = 165
eMotionMeas_FusedHeadingOffset = 166

def __init__(self, deviceNumber, controlPeriodMs, enablePeriodMs):

assert deviceNumber not in hal_data['CAN']
Expand All @@ -131,7 +159,7 @@ def __init__(self, deviceNumber, controlPeriodMs, enablePeriodMs):
# Initialize non-zero items or items that don't have an associated parameter
self.hal_data.update({
'type': 'talonsrx',
'sim_display': False, # used in sim
'sim_display': False, # used in sim

'override_limit_switch': 0,
'override_braketype': None,
Expand Down Expand Up @@ -164,7 +192,7 @@ def Destroy(self):
del self.hal_data

def Set(self, value):
self.hal_data['value'] = int(value*1023)
self.hal_data['value'] = int(value * 1023)

def SetParam(self, paramEnum, value):
self.hal_data[_srx_param_map[paramEnum]] = value
Expand Down Expand Up @@ -622,20 +650,20 @@ def __create_srx_param_map():
param_t.eSettingsChanged : 'settings_changed',
param_t.eQuadFilterEn : 'quad_filter_en',
param_t.ePidIaccum : 'pid_iaccum',
#param_t.eStatus1FrameRate : 94 # TALON_Status_1_General_10ms_t,
#param_t.eStatus2FrameRate : 95 # TALON_Status_2_Feedback_20ms_t,
#param_t.eStatus3FrameRate : 96 # TALON_Status_3_Enc_100ms_t,
#param_t.eStatus4FrameRate : 97 # TALON_Status_4_AinTempVbat_100ms_t,
#param_t.eStatus6FrameRate : 98 # TALON_Status_6_Eol_t,
#param_t.eStatus7FrameRate : 99 # TALON_Status_7_Debug_200ms_t,
# param_t.eStatus1FrameRate : 94 # TALON_Status_1_General_10ms_t,
# param_t.eStatus2FrameRate : 95 # TALON_Status_2_Feedback_20ms_t,
# param_t.eStatus3FrameRate : 96 # TALON_Status_3_Enc_100ms_t,
# param_t.eStatus4FrameRate : 97 # TALON_Status_4_AinTempVbat_100ms_t,
# param_t.eStatus6FrameRate : 98 # TALON_Status_6_Eol_t,
# param_t.eStatus7FrameRate : 99 # TALON_Status_7_Debug_200ms_t,
param_t.eClearPositionOnIdx : 'clear_position_on_idx',

param_t.ePeakPosOutput : 'peak_pos_output',
param_t.eNominalPosOutput : 'nominal_pos_output',
param_t.ePeakNegOutput : 'peak_neg_output',
param_t.eNominalNegOutput : 'nominal_neg_output',
param_t.eQuadIdxPolarity : 'quad_idx_polarity',
#param_t.eStatus8FrameRate : 109 # TALON_Status_8_PulseWid_100ms_t,
# param_t.eStatus8FrameRate : 109 # TALON_Status_8_PulseWid_100ms_t,
param_t.eAllowPosOverflow : 'allow_pos_overflow',
param_t.eProfileParamSlot0_AllowableClosedLoopErr: 'profile0_allowable_closed_loop_err',
param_t.eNumberPotTurns : 'number_pot_turns',
Expand All @@ -644,10 +672,29 @@ def __create_srx_param_map():
param_t.eAinPosition : 'analog_in_position',
param_t.eProfileParamVcompRate : 'profile_vcomp_rate',
param_t.eProfileParamSlot1_AllowableClosedLoopErr : 'profile1_allowable_closed_loop_err',
#param_t.eStatus9FrameRate : 118 # TALON_Status_9_MotProfBuffer_100ms_t,
# param_t.eStatus9FrameRate : 118 # TALON_Status_9_MotProfBuffer_100ms_t,
param_t.eMotionProfileHasUnderrunErr : 'motion_profile_has_underrun',
#param_t.eReserved120 : 120,
param_t.eLegacyControlMode : 'legacy_mode'
# param_t.eReserved120 : 120,
param_t.eLegacyControlMode : 'legacy_mode',
param_t.eMotMag_Accel: 'eMotMag_Accel',
param_t.eMotMag_VelCruise: 'eMotMag_VelCruise',
param_t.eStatus10FrameRate: 'eStatus10FrameRate',
param_t.eCurrentLimThreshold: 'eCurrentLimThreshold',
param_t.eBldcStatus1FrameRate: 'eBldcStatus1FrameRate',
param_t.eBldcStatus2FrameRate: 'eBldcStatus2FrameRate',
param_t.eBldcStatus3FrameRate: 'eBldcStatus3FrameRate',
param_t.eCustomParam0: 'eCustomParam0',
param_t.eCustomParam1: 'eCustomParam1',
param_t.ePersStorageSaving: 'ePersStorageSaving',
param_t.eClearPositionOnLimitF: 'eClearPositionOnLimitF',
param_t.eClearPositionOnLimitR: 'eClearPositionOnLimitR',
param_t.eMotionMeas_YawOffset: 'eMotionMeas_YawOffset',
param_t.eMotionMeas_CompassOffset: 'eMotionMeas_CompassOffset',
param_t.eMotionMeas_BetaGain: 'eMotionMeas_BetaGain',
param_t.eMotionMeas_Reserved163: 'eMotionMeas_Reserved163',
param_t.eMotionMeas_GyroNoMotionCal: 'eMotionMeas_GyroNoMotionCal',
param_t.eMotionMeas_EnterCalibration: 'eMotionMeas_EnterCalibration',
param_t.eMotionMeas_FusedHeadingOffset: 'eMotionMeas_FusedHeadingOffset'
}

def __create_srx_sensor_position_map():
Expand Down
3 changes: 2 additions & 1 deletion ctre/_impl/sim_ui.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,8 @@ class CtreUI:
tsrxc.kMode_PositionCloseLoop:'Position',
tsrxc.kMode_SlaveFollower:'Follower',
tsrxc.kMode_VelocityCloseLoop:'Speed',
tsrxc.kMode_VoltCompen:'Voltage'
tsrxc.kMode_VoltCompen:'Voltage',
tsrxc.kMode_MotionMagic:'Motion Magic'
}

def __init__(self):
Expand Down
24 changes: 24 additions & 0 deletions examples/CANTalon_MotionMagic/instrum.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
from wpilib import SmartDashboard
import ctre


class Instrum():
loops = 0

@staticmethod
def process(tal, sb):
# Smart dash plots
SmartDashboard.putNumber('RPM', tal.getSpeed())
SmartDashboard.putNumber('Pos', tal.getPosition())
SmartDashboard.putNumber('AppliedThrottle', (tal.getOutputVoltage() / tal.getBusVoltage()) * 1023)
SmartDashboard.putNumber('ClosedLoopError', tal.getClosedLoopError())
if tal.getControlMode() is ctre.CANTalon.ControlMode.MotionMagic:
#These API calls will be added in our next release.
#SmartDashboard.putNumber("ActTrajVelocity", tal.getMotionMagicActTrajVelocity());
# SmartDashboard.putNumber("ActTrajPosition", tal.getMotionMagicActTrajPosition());
pass

# Periodically print to console
if Instrum.loops >= 10:
print(sb)
Instrum.loops = 0
73 changes: 73 additions & 0 deletions examples/CANTalon_MotionMagic/robot.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,73 @@
"""
Example demonstrating the motion magic control mode.
Tested with Logitech F710 USB Gamepad inserted into Driver Station.
Be sure to select the correct feedback sensor using SetFeedbackDevice() below.
After deploying/debugging this to your RIO, first use the left Y-stick
to throttle the Talon manually. This will confirm your hardware setup/sensors
and will allow you to take initial measurements.
Be sure to confirm that when the Talon is driving forward (green) the
position sensor is moving in a positive direction. If this is not the
cause, flip the boolean input to the reverseSensor() call below.
Once you've ensured your feedback device is in-phase with the motor,
and followed the walk-through in the Talon SRX Software Reference Manual,
use button1 to motion-magic servo to target position specified by the gamepad stick.
"""
import wpilib
import ctre
from examples.CANTalon_MotionMagic.instrum import Instrum


class MyRobot(wpilib.IterativeRobot):

def robotInit(self):
self.talon = ctre.CANTalon(3)
self.joystick = wpilib.Joystick(0)

self.talon.setFeedbackDevice(ctre.CANTalon.FeedbackDevice.CtreMagEncoder_Relative)
# self.talon.configEncoderCodesPerRev(XXX), if using FeedbackDevice.QuadEncoder
# self.talon.configPotentiometerTurns(XXX), if using FeedbackDevice.AnalogEncoder or AnalogPot

# Set the peak nominal outputs. 12V means full
self.talon.configNominalOutputVoltage(+0.0, -0.0)
self.talon.configPeakOutputVoltage(12.0, -12.0)

# Set closed loop gains in slot0 - see documentation
self.talon.setProfile(0)
self.talon.setPID(0, 0, 0, 0) # P,I,D,F = 0

# Set acceleration and vcruise velocity - see documentation
self.talon.setMotionMagicCruiseVelocity(0)
self.talon.setMotionMagicAcceleration(0)

def teleopPeriodic(self):
# Get gamepad axis - forward stick is positive
leftYstick = -1 * self.joystick.getAxis(wpilib.Joystick.AxisType.kY)
# Calculate the percent motor output
motor_output = self.talon.getOutputVoltage() / self.talon.getBusVoltage()

# Prepare line to print
sb = '\tout:{}\tspd:{}'.format(motor_output, self.talon.getSpeed())

if self.joystick.getRawButton(1):
targetPos = leftYstick * 10 # 10 rotations in either direction
self.talon.changeControlMode(ctre.CANTalon.ControlMode.MotionMagic)
self.talon.set(targetPos)

# Append more lines to print
sb += '\terr:{}\ttrg{}'.format(self.talon.getClosedLoopError(), targetPos)
else:
# Percent voltage mode
self.talon.changeControlMode(ctre.CANTalon.ControlMode.PercentVbus)
self.talon.set(leftYstick)

# Instrumentation
Instrum.process(self.talon, sb)

sb = ''

if __name__ == '__main__':
wpilib.run(MyRobot)

0 comments on commit 893347b

Please sign in to comment.