Brian Silverman | 26e4e52 | 2015-12-17 01:56:40 -0500 | [diff] [blame^] | 1 | /*----------------------------------------------------------------------------*/ |
| 2 | /* Copyright (c) FIRST 2008. 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 $(WIND_BASE)/WPILib. */ |
| 5 | /*----------------------------------------------------------------------------*/ |
| 6 | |
| 7 | #include "PWM.h" |
| 8 | |
| 9 | //#include "NetworkCommunication/UsageReporting.h" |
| 10 | #include "Utility.h" |
| 11 | #include "WPIErrors.h" |
| 12 | |
| 13 | const float PWM::kDefaultPwmPeriod = 5.05; |
| 14 | const float PWM::kDefaultPwmCenter = 1.5; |
| 15 | const int32_t PWM::kDefaultPwmStepsDown = 1000; |
| 16 | const int32_t PWM::kPwmDisabled = 0; |
| 17 | |
| 18 | /** |
| 19 | * Allocate a PWM given a channel number. |
| 20 | * |
| 21 | * Checks channel value range and allocates the appropriate channel. |
| 22 | * The allocation is only done to help users ensure that they don't double |
| 23 | * assign channels. |
| 24 | * @param channel The PWM channel number. 0-9 are on-board, 10-19 are on the MXP |
| 25 | * port |
| 26 | */ |
| 27 | PWM::PWM(uint32_t channel) |
| 28 | { |
| 29 | char buf[64]; |
| 30 | |
| 31 | if (!CheckPWMChannel(channel)) |
| 32 | { |
| 33 | snprintf(buf, 64, "PWM Channel %d", channel); |
| 34 | wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf); |
| 35 | return; |
| 36 | } |
| 37 | |
| 38 | sprintf(buf, "pwm/%d", channel); |
| 39 | impl = new SimContinuousOutput(buf); |
| 40 | m_channel = channel; |
| 41 | m_eliminateDeadband = false; |
| 42 | |
| 43 | m_centerPwm = kPwmDisabled; // In simulation, the same thing. |
| 44 | } |
| 45 | |
| 46 | PWM::~PWM() { |
| 47 | if (m_table != nullptr) m_table->RemoveTableListener(this); |
| 48 | } |
| 49 | |
| 50 | /** |
| 51 | * Optionally eliminate the deadband from a speed controller. |
| 52 | * @param eliminateDeadband If true, set the motor curve on the Jaguar to eliminate |
| 53 | * the deadband in the middle of the range. Otherwise, keep the full range without |
| 54 | * modifying any values. |
| 55 | */ |
| 56 | void PWM::EnableDeadbandElimination(bool eliminateDeadband) |
| 57 | { |
| 58 | m_eliminateDeadband = eliminateDeadband; |
| 59 | } |
| 60 | |
| 61 | /** |
| 62 | * Set the bounds on the PWM values. |
| 63 | * This sets the bounds on the PWM values for a particular each type of controller. The values |
| 64 | * determine the upper and lower speeds as well as the deadband bracket. |
| 65 | * @param max The Minimum pwm value |
| 66 | * @param deadbandMax The high end of the deadband range |
| 67 | * @param center The center speed (off) |
| 68 | * @param deadbandMin The low end of the deadband range |
| 69 | * @param min The minimum pwm value |
| 70 | */ |
| 71 | void PWM::SetBounds(int32_t max, int32_t deadbandMax, int32_t center, int32_t deadbandMin, int32_t min) |
| 72 | { |
| 73 | // Nothing to do in simulation. |
| 74 | } |
| 75 | |
| 76 | |
| 77 | /** |
| 78 | * Set the bounds on the PWM pulse widths. |
| 79 | * This sets the bounds on the PWM values for a particular type of controller. The values |
| 80 | * determine the upper and lower speeds as well as the deadband bracket. |
| 81 | * @param max The max PWM pulse width in ms |
| 82 | * @param deadbandMax The high end of the deadband range pulse width in ms |
| 83 | * @param center The center (off) pulse width in ms |
| 84 | * @param deadbandMin The low end of the deadband pulse width in ms |
| 85 | * @param min The minimum pulse width in ms |
| 86 | */ |
| 87 | void PWM::SetBounds(double max, double deadbandMax, double center, double deadbandMin, double min) |
| 88 | { |
| 89 | // Nothing to do in simulation. |
| 90 | } |
| 91 | |
| 92 | /** |
| 93 | * Set the PWM value based on a position. |
| 94 | * |
| 95 | * This is intended to be used by servos. |
| 96 | * |
| 97 | * @pre SetMaxPositivePwm() called. |
| 98 | * @pre SetMinNegativePwm() called. |
| 99 | * |
| 100 | * @param pos The position to set the servo between 0.0 and 1.0. |
| 101 | */ |
| 102 | void PWM::SetPosition(float pos) |
| 103 | { |
| 104 | if (pos < 0.0) |
| 105 | { |
| 106 | pos = 0.0; |
| 107 | } |
| 108 | else if (pos > 1.0) |
| 109 | { |
| 110 | pos = 1.0; |
| 111 | } |
| 112 | |
| 113 | impl->Set(pos); |
| 114 | } |
| 115 | |
| 116 | /** |
| 117 | * Get the PWM value in terms of a position. |
| 118 | * |
| 119 | * This is intended to be used by servos. |
| 120 | * |
| 121 | * @pre SetMaxPositivePwm() called. |
| 122 | * @pre SetMinNegativePwm() called. |
| 123 | * |
| 124 | * @return The position the servo is set to between 0.0 and 1.0. |
| 125 | */ |
| 126 | float PWM::GetPosition() const |
| 127 | { |
| 128 | float value = impl->Get(); |
| 129 | if (value < 0.0) |
| 130 | { |
| 131 | return 0.0; |
| 132 | } |
| 133 | else if (value > 1.0) |
| 134 | { |
| 135 | return 1.0; |
| 136 | } |
| 137 | else |
| 138 | { |
| 139 | return value; |
| 140 | } |
| 141 | } |
| 142 | |
| 143 | /** |
| 144 | * Set the PWM value based on a speed. |
| 145 | * |
| 146 | * This is intended to be used by speed controllers. |
| 147 | * |
| 148 | * @pre SetMaxPositivePwm() called. |
| 149 | * @pre SetMinPositivePwm() called. |
| 150 | * @pre SetCenterPwm() called. |
| 151 | * @pre SetMaxNegativePwm() called. |
| 152 | * @pre SetMinNegativePwm() called. |
| 153 | * |
| 154 | * @param speed The speed to set the speed controller between -1.0 and 1.0. |
| 155 | */ |
| 156 | void PWM::SetSpeed(float speed) |
| 157 | { |
| 158 | // clamp speed to be in the range 1.0 >= speed >= -1.0 |
| 159 | if (speed < -1.0) |
| 160 | { |
| 161 | speed = -1.0; |
| 162 | } |
| 163 | else if (speed > 1.0) |
| 164 | { |
| 165 | speed = 1.0; |
| 166 | } |
| 167 | |
| 168 | impl->Set(speed); |
| 169 | } |
| 170 | |
| 171 | /** |
| 172 | * Get the PWM value in terms of speed. |
| 173 | * |
| 174 | * This is intended to be used by speed controllers. |
| 175 | * |
| 176 | * @pre SetMaxPositivePwm() called. |
| 177 | * @pre SetMinPositivePwm() called. |
| 178 | * @pre SetMaxNegativePwm() called. |
| 179 | * @pre SetMinNegativePwm() called. |
| 180 | * |
| 181 | * @return The most recently set speed between -1.0 and 1.0. |
| 182 | */ |
| 183 | float PWM::GetSpeed() const |
| 184 | { |
| 185 | float value = impl->Get(); |
| 186 | if (value > 1.0) |
| 187 | { |
| 188 | return 1.0; |
| 189 | } |
| 190 | else if (value < -1.0) |
| 191 | { |
| 192 | return -1.0; |
| 193 | } |
| 194 | else |
| 195 | { |
| 196 | return value; |
| 197 | } |
| 198 | } |
| 199 | |
| 200 | /** |
| 201 | * Set the PWM value directly to the hardware. |
| 202 | * |
| 203 | * Write a raw value to a PWM channel. |
| 204 | * |
| 205 | * @param value Raw PWM value. |
| 206 | */ |
| 207 | void PWM::SetRaw(unsigned short value) |
| 208 | { |
| 209 | wpi_assert(value == kPwmDisabled); |
| 210 | impl->Set(0); |
| 211 | } |
| 212 | |
| 213 | /** |
| 214 | * Slow down the PWM signal for old devices. |
| 215 | * |
| 216 | * @param mult The period multiplier to apply to this channel |
| 217 | */ |
| 218 | void PWM::SetPeriodMultiplier(PeriodMultiplier mult) |
| 219 | { |
| 220 | // Do nothing in simulation. |
| 221 | } |
| 222 | |
| 223 | |
| 224 | void PWM::ValueChanged(ITable* source, llvm::StringRef key, |
| 225 | std::shared_ptr<nt::Value> value, bool isNew) { |
| 226 | if (!value->IsDouble()) return; |
| 227 | SetSpeed(value->GetDouble()); |
| 228 | } |
| 229 | |
| 230 | void PWM::UpdateTable() { |
| 231 | if (m_table != nullptr) { |
| 232 | m_table->PutNumber("Value", GetSpeed()); |
| 233 | } |
| 234 | } |
| 235 | |
| 236 | void PWM::StartLiveWindowMode() { |
| 237 | SetSpeed(0); |
| 238 | if (m_table != nullptr) { |
| 239 | m_table->AddTableListener("Value", this, true); |
| 240 | } |
| 241 | } |
| 242 | |
| 243 | void PWM::StopLiveWindowMode() { |
| 244 | SetSpeed(0); |
| 245 | if (m_table != nullptr) { |
| 246 | m_table->RemoveTableListener(this); |
| 247 | } |
| 248 | } |
| 249 | |
| 250 | std::string PWM::GetSmartDashboardType() const { |
| 251 | return "Speed Controller"; |
| 252 | } |
| 253 | |
| 254 | void PWM::InitTable(std::shared_ptr<ITable> subTable) { |
| 255 | m_table = subTable; |
| 256 | UpdateTable(); |
| 257 | } |
| 258 | |
| 259 | std::shared_ptr<ITable> PWM::GetTable() const { |
| 260 | return m_table; |
| 261 | } |