2014-12-05 09:19:27 -08:00
|
|
|
/*----------------------------------------------------------------------------*/
|
|
|
|
|
/* Copyright (c) FIRST 2008. All Rights Reserved. */
|
|
|
|
|
/* Open Source Software - may be modified and shared by FRC teams. The code */
|
|
|
|
|
/* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */
|
|
|
|
|
/*----------------------------------------------------------------------------*/
|
|
|
|
|
|
|
|
|
|
#include "TalonSRX.h"
|
|
|
|
|
|
2014-12-12 18:01:24 -05:00
|
|
|
//#include "NetworkCommunication/UsageReporting.h"
|
|
|
|
|
#include "LiveWindow/LiveWindow.h"
|
2014-12-05 09:19:27 -08:00
|
|
|
|
2014-12-12 18:01:24 -05:00
|
|
|
/**
|
|
|
|
|
* Common initialization code called by all constructors.
|
|
|
|
|
*
|
|
|
|
|
* Note that the TalonSRX uses the following bounds for PWM values. These values should work reasonably well for
|
2014-12-29 14:09:37 -05:00
|
|
|
* most controllers, but if users experience issues such as asymmetric behaviour around
|
2014-12-12 18:01:24 -05:00
|
|
|
* the deadband or inability to saturate the controller in either direction, calibration is recommended.
|
|
|
|
|
* The calibration procedure can be found in the TalonSRX User Manual available from Cross The Road Electronics.
|
2014-12-29 14:09:37 -05:00
|
|
|
* 2.004ms = full "forward"
|
|
|
|
|
* 1.52ms = the "high end" of the deadband range
|
|
|
|
|
* 1.50ms = center of the deadband range (off)
|
|
|
|
|
* 1.48ms = the "low end" of the deadband range
|
|
|
|
|
* 0.997ms = full "reverse"
|
2014-12-12 18:01:24 -05:00
|
|
|
*/
|
|
|
|
|
void TalonSRX::InitTalonSRX() {
|
2014-12-13 18:06:43 -05:00
|
|
|
SetBounds(2.004, 1.52, 1.50, 1.48, .997);
|
2014-12-12 18:01:24 -05:00
|
|
|
SetPeriodMultiplier(kPeriodMultiplier_1X);
|
|
|
|
|
SetRaw(m_centerPwm);
|
|
|
|
|
SetZeroLatch();
|
|
|
|
|
|
2015-04-30 16:22:46 -04:00
|
|
|
HALReport(HALUsageReporting::kResourceType_TalonSRX, GetChannel());
|
2014-12-12 18:01:24 -05:00
|
|
|
LiveWindow::GetInstance()->AddActuator("TalonSRX", GetChannel(), this);
|
2015-03-24 15:01:17 -04:00
|
|
|
m_isInverted = false;
|
2014-12-12 18:01:24 -05:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
2014-12-29 14:09:37 -05:00
|
|
|
* Construct a TalonSRX connected via PWM
|
|
|
|
|
* @param channel The PWM channel that the TalonSRX is attached to. 0-9 are on-board, 10-19 are on the MXP port
|
2014-12-12 18:01:24 -05:00
|
|
|
*/
|
|
|
|
|
TalonSRX::TalonSRX(uint32_t channel) : SafePWM(channel)
|
|
|
|
|
{
|
|
|
|
|
InitTalonSRX();
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
TalonSRX::~TalonSRX()
|
|
|
|
|
{
|
2014-12-05 09:19:27 -08:00
|
|
|
}
|
|
|
|
|
|
2014-12-12 18:01:24 -05:00
|
|
|
/**
|
|
|
|
|
* Set the PWM value.
|
|
|
|
|
*
|
|
|
|
|
* The PWM value is set using a range of -1.0 to 1.0, appropriately
|
|
|
|
|
* scaling the value for the FPGA.
|
|
|
|
|
*
|
|
|
|
|
* @param speed The speed value between -1.0 and 1.0 to set.
|
|
|
|
|
* @param syncGroup Unused interface.
|
|
|
|
|
*/
|
|
|
|
|
void TalonSRX::Set(float speed, uint8_t syncGroup)
|
|
|
|
|
{
|
|
|
|
|
SetSpeed(speed);
|
2014-12-05 09:19:27 -08:00
|
|
|
}
|
|
|
|
|
|
2014-12-12 18:01:24 -05:00
|
|
|
/**
|
|
|
|
|
* Get the recently set value of the PWM.
|
|
|
|
|
*
|
|
|
|
|
* @return The most recently set value for the PWM between -1.0 and 1.0.
|
|
|
|
|
*/
|
2015-06-19 17:23:54 -07:00
|
|
|
float TalonSRX::Get() const
|
2014-12-12 18:01:24 -05:00
|
|
|
{
|
|
|
|
|
return GetSpeed();
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* Common interface for disabling a motor.
|
|
|
|
|
*/
|
|
|
|
|
void TalonSRX::Disable()
|
|
|
|
|
{
|
|
|
|
|
SetRaw(kPwmDisabled);
|
|
|
|
|
}
|
2015-03-24 15:01:17 -04:00
|
|
|
/**
|
|
|
|
|
* common interface for inverting direction of a speed controller
|
|
|
|
|
* @param isInverted The state of inversion true is inverted
|
|
|
|
|
*/
|
|
|
|
|
void TalonSRX::SetInverted(bool isInverted){
|
|
|
|
|
m_isInverted = isInverted;
|
|
|
|
|
}
|
2014-12-12 18:01:24 -05:00
|
|
|
/**
|
|
|
|
|
* Write out the PID value as seen in the PIDOutput base object.
|
|
|
|
|
*
|
|
|
|
|
* @param output Write out the PWM value as was found in the PIDController
|
|
|
|
|
*/
|
|
|
|
|
void TalonSRX::PIDWrite(float output)
|
|
|
|
|
{
|
|
|
|
|
Set(output);
|
|
|
|
|
}
|