blob: a53d5a06a0052eac2b0462d5735bfb0382b2ce28 [file] [log] [blame]
Brian Silverman6260c092018-01-14 15:21:36 -08001#include "motors/core/kinetis.h"
2
3#include <stdio.h>
4#include <inttypes.h>
5
6#include <atomic>
7#include <cmath>
8
9#include "motors/core/time.h"
10#include "motors/motor.h"
11#include "motors/peripheral/adc.h"
12#include "motors/peripheral/can.h"
13#include "motors/pistol_grip/motor_controls.h"
14#include "motors/usb/cdc.h"
15#include "motors/usb/usb.h"
16#include "motors/util.h"
17#include "frc971/control_loops/drivetrain/integral_haptic_wheel.h"
18#include "frc971/control_loops/drivetrain/integral_haptic_trigger.h"
19
20#define MOTOR0_PWM_FTM FTM3
21#define MOTOR0_ENCODER_FTM FTM2
22#define MOTOR1_PWM_FTM FTM0
23#define MOTOR1_ENCODER_FTM FTM1
24
25extern const float kWheelCoggingTorque[4096];
26extern const float kTriggerCoggingTorque[4096];
27
28namespace frc971 {
29namespace salsa {
30namespace {
31
32using ::frc971::control_loops::drivetrain::MakeIntegralHapticTriggerPlant;
33using ::frc971::control_loops::drivetrain::MakeIntegralHapticTriggerObserver;
34using ::frc971::control_loops::drivetrain::MakeIntegralHapticWheelPlant;
35using ::frc971::control_loops::drivetrain::MakeIntegralHapticWheelObserver;
36
37constexpr float kHapticWheelCurrentLimit = static_cast<float>(
38 ::frc971::control_loops::drivetrain::kHapticWheelCurrentLimit);
39constexpr float kHapticTriggerCurrentLimit = static_cast<float>(
40 ::frc971::control_loops::drivetrain::kHapticTriggerCurrentLimit);
41
42::std::atomic<Motor *> global_motor0{nullptr}, global_motor1{nullptr};
43::std::atomic<teensy::AcmTty *> global_stdout{nullptr};
44
45// Angle last time the current loop ran.
46::std::atomic<float> global_wheel_angle{0.0f};
47::std::atomic<float> global_trigger_angle{0.0f};
48
49// Wheel observer/plant.
50::std::atomic<StateFeedbackObserver<3, 1, 1, float> *> global_wheel_observer{
51 nullptr};
52::std::atomic<StateFeedbackPlant<3, 1, 1, float> *> global_wheel_plant{nullptr};
53// Throttle observer/plant.
54::std::atomic<StateFeedbackObserver<3, 1, 1, float> *> global_trigger_observer{
55 nullptr};
56::std::atomic<StateFeedbackPlant<3, 1, 1, float> *> global_trigger_plant{
57 nullptr};
58
59// Torques for the current loop to apply.
60::std::atomic<float> global_wheel_current{0.0f};
61::std::atomic<float> global_trigger_torque{0.0f};
62
63constexpr int kSwitchingDivisor = 2;
64
65float analog_ratio(uint16_t reading) {
66 static constexpr uint16_t kMin = 260, kMax = 3812;
67 return static_cast<float>(::std::max(::std::min(reading, kMax), kMin) -
68 kMin) /
69 static_cast<float>(kMax - kMin);
70}
71
72constexpr float InterpolateFloat(float x1, float x0, float y1, float y0, float x) {
73 return (x - x0) * (y1 - y0) / (x1 - x0) + y0;
74}
75
76float absolute_wheel(float wheel_position) {
77 if (wheel_position < 0.43f) {
78 wheel_position += 1.0f;
79 }
80 wheel_position -= 0.462f + 0.473f;
81 return wheel_position;
82}
83
84extern "C" {
85
86void *__stack_chk_guard = (void *)0x67111971;
87void __stack_chk_fail() {
88 while (true) {
89 GPIOC_PSOR = (1 << 5);
90 printf("Stack corruption detected\n");
91 delay(1000);
92 GPIOC_PCOR = (1 << 5);
93 delay(1000);
94 }
95}
96
97int _write(int /*file*/, char *ptr, int len) {
98 teensy::AcmTty *const tty = global_stdout.load(::std::memory_order_acquire);
99 if (tty != nullptr) {
100 return tty->Write(ptr, len);
101 }
102 return 0;
103}
104
105extern uint32_t __bss_ram_start__[], __bss_ram_end__[];
106extern uint32_t __data_ram_start__[], __data_ram_end__[];
107extern uint32_t __heap_start__[], __heap_end__[];
108extern uint32_t __stack_end__[];
109
110} // extern "C"
111
112constexpr float kWheelMaxExtension = 1.0f;
113constexpr float kWheelFrictionMax = 0.2f;
114float WheelCenteringCurrent(float scalar, float angle, float velocity) {
115 float friction_goal_current = -angle * 10.0f;
116 if (friction_goal_current > kWheelFrictionMax) {
117 friction_goal_current = kWheelFrictionMax;
118 } else if (friction_goal_current < -kWheelFrictionMax) {
119 friction_goal_current = -kWheelFrictionMax;
120 }
121
122 constexpr float kWheelSpringNonlinearity = 0.45f;
123
124 float goal_current = -((1.0f - kWheelSpringNonlinearity) * angle +
125 kWheelSpringNonlinearity * angle * angle * angle) *
126 6.0f -
127 velocity * 0.04f;
128 if (goal_current > 5.0f - scalar) {
129 goal_current = 5.0f - scalar;
130 } else if (goal_current < -5.0f + scalar) {
131 goal_current = -5.0f + scalar;
132 }
133
134 return goal_current * scalar + friction_goal_current;
135}
136
137extern "C" void ftm0_isr() {
138 SmallAdcReadings readings;
139 {
140 DisableInterrupts disable_interrupts;
141 readings = AdcReadSmall1(disable_interrupts);
142 }
143 uint32_t encoder =
144 global_motor1.load(::std::memory_order_relaxed)->wrapped_encoder();
145 int32_t absolute_encoder = global_motor1.load(::std::memory_order_relaxed)
146 ->absolute_encoder(encoder);
147
148 const float angle = absolute_encoder / static_cast<float>((15320 - 1488) / 2);
149 global_wheel_angle.store(angle);
150
151 float goal_current = -global_wheel_current.load(::std::memory_order_relaxed) +
152 kWheelCoggingTorque[encoder];
153
154 global_motor1.load(::std::memory_order_relaxed)->SetGoalCurrent(goal_current);
155 global_motor1.load(::std::memory_order_relaxed)
156 ->HandleInterrupt(BalanceSimpleReadings(readings.currents), encoder);
157}
158
159constexpr float kTriggerMaxExtension = -1.00f;
160constexpr float kTriggerCenter = 0.0f;
161float TriggerCenteringCurrent(float trigger_angle) {
162 float goal_current = (kTriggerCenter - trigger_angle) * 3.0f;
163 if (goal_current < -1.0f) {
164 goal_current = -1.0f;
165 } else if (goal_current > 1.0f) {
166 goal_current = 1.0f;
167 if (trigger_angle < kTriggerMaxExtension) {
168 goal_current -= (30.0f * (trigger_angle - kTriggerMaxExtension));
169 if (goal_current > 2.0f) {
170 goal_current = 2.0f;
171 }
172 }
173 }
174 return goal_current;
175}
176
177extern "C" void ftm3_isr() {
178 SmallAdcReadings readings;
179 {
180 DisableInterrupts disable_interrupts;
181 readings = AdcReadSmall0(disable_interrupts);
182 }
183 uint32_t encoder =
184 global_motor0.load(::std::memory_order_relaxed)->wrapped_encoder();
185 int32_t absolute_encoder = global_motor0.load(::std::memory_order_relaxed)
186 ->absolute_encoder(encoder);
187
188 float trigger_angle = absolute_encoder / 1370.f;
189
190 const float goal_current =
191 -global_trigger_torque.load(::std::memory_order_relaxed) +
192 kTriggerCoggingTorque[encoder];
193
194 global_motor0.load(::std::memory_order_relaxed)->SetGoalCurrent(goal_current);
195 global_motor0.load(::std::memory_order_relaxed)
196 ->HandleInterrupt(BalanceSimpleReadings(readings.currents), encoder);
197
198
199 global_trigger_angle.store(trigger_angle);
200}
201
202
203int ConvertFloat16(float val) {
204 int result = static_cast<int>(val * 32768.0f) + 32768;
205 if (result > 0xffff) {
206 result = 0xffff;
207 } else if (result < 0) {
208 result = 0;
209 }
210 return result;
211}
212int ConvertFloat14(float val) {
213 int result = static_cast<int>(val * 8192.0f) + 8192;
214 if (result > 0x3fff) {
215 result = 0x3fff;
216 } else if (result < 0) {
217 result = 0;
218 }
219 return result;
220}
221
222extern "C" void pit3_isr() {
223 PIT_TFLG3 = 1;
224 const float absolute_trigger_angle =
225 global_trigger_angle.load(::std::memory_order_relaxed);
226 const float absolute_wheel_angle =
227 global_wheel_angle.load(::std::memory_order_relaxed);
228
229 // Force a barrier here so we sample everything guaranteed at the beginning.
230 __asm__("" ::: "memory");
231 const float absolute_wheel_angle_radians =
232 absolute_wheel_angle * static_cast<float>(M_PI) * (338.16f / 360.0f);
233 const float absolute_trigger_angle_radians =
234 absolute_trigger_angle * static_cast<float>(M_PI) * (45.0f / 360.0f);
235
236 static uint32_t last_command_time = 0;
237 static float trigger_goal_position = 0.0f;
238 static float trigger_goal_velocity = 0.0f;
239 static float trigger_haptic_current = 0.0f;
240 static bool trigger_centering = true;
241 static bool trigger_haptics = false;
242 {
243 uint8_t data[8];
244 int length;
245 can_receive_command(data, &length, 0);
246 if (length > 0) {
247 last_command_time = micros();
248 trigger_goal_position =
249 static_cast<float>(
250 static_cast<int32_t>(static_cast<uint32_t>(data[0]) |
251 (static_cast<uint32_t>(data[1]) << 8)) -
252 32768) /
253 32768.0f * M_PI / 8.0;
254 trigger_goal_velocity =
255 static_cast<float>(
256 static_cast<int32_t>(static_cast<uint32_t>(data[2]) |
257 (static_cast<uint32_t>(data[3]) << 8)) -
258 32768) /
259 32768.0f * 4.0f;
260
261 trigger_haptic_current =
262 static_cast<float>(
263 static_cast<int32_t>(static_cast<uint32_t>(data[4]) |
264 (static_cast<uint32_t>(data[5]) << 8)) -
265 32768) /
266 32768.0f * 2.0f;
267 if (trigger_haptic_current > kHapticTriggerCurrentLimit) {
268 trigger_haptic_current = kHapticTriggerCurrentLimit;
269 } else if (trigger_haptic_current < -kHapticTriggerCurrentLimit) {
270 trigger_haptic_current = -kHapticTriggerCurrentLimit;
271 }
272 trigger_centering = !!(data[7] & 0x01);
273 trigger_haptics = !!(data[7] & 0x02);
274 }
275 }
276
277 static float wheel_goal_position = 0.0f;
278 static float wheel_goal_velocity = 0.0f;
279 static float wheel_haptic_current = 0.0f;
280 static float wheel_kp = 0.0f;
281 static bool wheel_centering = true;
282 static float wheel_centering_scalar = 0.25f;
283 {
284 uint8_t data[8];
285 int length;
286 can_receive_command(data, &length, 1);
287 if (length == 8) {
288 last_command_time = micros();
289 wheel_goal_position =
290 static_cast<float>(
291 static_cast<int32_t>(static_cast<uint32_t>(data[0]) |
292 (static_cast<uint32_t>(data[1]) << 8)) -
293 32768) /
294 32768.0f * M_PI;
295 wheel_goal_velocity =
296 static_cast<float>(
297 static_cast<int32_t>(static_cast<uint32_t>(data[2]) |
298 (static_cast<uint32_t>(data[3]) << 8)) -
299 32768) /
300 32768.0f * 10.0f;
301
302 wheel_haptic_current =
303 static_cast<float>(
304 static_cast<int32_t>(static_cast<uint32_t>(data[4]) |
305 (static_cast<uint32_t>(data[5]) << 8)) -
306 32768) /
307 32768.0f * 2.0f;
308 if (wheel_haptic_current > kHapticWheelCurrentLimit) {
309 wheel_haptic_current = kHapticWheelCurrentLimit;
310 } else if (wheel_haptic_current < -kHapticWheelCurrentLimit) {
311 wheel_haptic_current = -kHapticWheelCurrentLimit;
312 }
313 wheel_kp = static_cast<float>(data[6]) * 30.0f / 255.0f;
314 wheel_centering = !!(data[7] & 0x01);
315 wheel_centering_scalar = ((data[7] >> 1) & 0x7f) / 127.0f;
316 }
317 }
318
319 static constexpr uint32_t kTimeout = 100000;
320 if (!time_after(time_add(last_command_time, kTimeout), micros())) {
321 last_command_time = time_subtract(micros(), kTimeout);
322 trigger_goal_position = 0.0f;
323 trigger_goal_velocity = 0.0f;
324 trigger_haptic_current = 0.0f;
325 trigger_centering = true;
326 trigger_haptics = false;
327
328 wheel_goal_position = 0.0f;
329 wheel_goal_velocity = 0.0f;
330 wheel_haptic_current = 0.0f;
331 wheel_centering = true;
332 wheel_centering_scalar = 0.25f;
333 }
334
335 StateFeedbackPlant<3, 1, 1, float> *const trigger_plant =
336 global_trigger_plant.load(::std::memory_order_relaxed);
337 StateFeedbackObserver<3, 1, 1, float> *const trigger_observer =
338 global_trigger_observer.load(::std::memory_order_relaxed);
339 ::Eigen::Matrix<float, 1, 1> trigger_Y;
340 trigger_Y << absolute_trigger_angle_radians;
341 trigger_observer->Correct(*trigger_plant,
342 ::Eigen::Matrix<float, 1, 1>::Zero(), trigger_Y);
343
344 StateFeedbackPlant<3, 1, 1, float> *const wheel_plant =
345 global_wheel_plant.load(::std::memory_order_relaxed);
346 StateFeedbackObserver<3, 1, 1, float> *const wheel_observer =
347 global_wheel_observer.load(::std::memory_order_relaxed);
348 ::Eigen::Matrix<float, 1, 1> wheel_Y;
349 wheel_Y << absolute_wheel_angle_radians;
350 wheel_observer->Correct(*wheel_plant, ::Eigen::Matrix<float, 1, 1>::Zero(),
351 wheel_Y);
352
353 float kWheelD = (wheel_kp - 10.0f) * (0.25f - 0.20f) / 5.0f + 0.20f;
354 if (wheel_kp < 0.5f) {
355 kWheelD = wheel_kp * 0.05f / 0.5f;
356 } else if (wheel_kp < 1.0f) {
357 kWheelD = InterpolateFloat(1.0f, 0.5f, 0.06f, 0.05f, wheel_kp);
358 } else if (wheel_kp < 2.0f) {
359 kWheelD = InterpolateFloat(2.0f, 1.0f, 0.08f, 0.06f, wheel_kp);
360 } else if (wheel_kp < 3.0f) {
361 kWheelD = InterpolateFloat(3.0f, 2.0f, 0.10f, 0.08f, wheel_kp);
362 } else if (wheel_kp < 5.0f) {
363 kWheelD = InterpolateFloat(5.0f, 3.0f, 0.13f, 0.10f, wheel_kp);
364 } else if (wheel_kp < 10.0f) {
365 kWheelD = InterpolateFloat(10.0f, 5.0f, 0.20f, 0.13f, wheel_kp);
366 }
367
368 float wheel_goal_current = wheel_haptic_current;
369
370 wheel_goal_current +=
371 (wheel_goal_position - absolute_wheel_angle_radians) * wheel_kp +
372 (wheel_goal_velocity - wheel_observer->X_hat()(1, 0)) * kWheelD;
373
374 // Compute the torques to apply to each motor.
375 if (wheel_centering) {
376 wheel_goal_current +=
377 WheelCenteringCurrent(wheel_centering_scalar, absolute_wheel_angle,
378 wheel_observer->X_hat()(1, 0));
379 }
380
381 if (wheel_goal_current > kHapticWheelCurrentLimit) {
382 wheel_goal_current = kHapticWheelCurrentLimit;
383 } else if (wheel_goal_current < -kHapticWheelCurrentLimit) {
384 wheel_goal_current = -kHapticWheelCurrentLimit;
385 }
386 global_wheel_current.store(wheel_goal_current, ::std::memory_order_relaxed);
387
388 constexpr float kTriggerP =
389 static_cast<float>(::frc971::control_loops::drivetrain::kHapticTriggerP);
390 constexpr float kTriggerD =
391 static_cast<float>(::frc971::control_loops::drivetrain::kHapticTriggerD);
392 float trigger_goal_current = trigger_haptic_current;
393 if (trigger_haptics) {
394 trigger_goal_current +=
395 (trigger_goal_position - absolute_trigger_angle_radians) * kTriggerP +
396 (trigger_goal_velocity - trigger_observer->X_hat()(1, 0)) * kTriggerD;
397 }
398
399 if (trigger_centering) {
400 trigger_goal_current += TriggerCenteringCurrent(absolute_trigger_angle);
401 }
402
403 if (trigger_goal_current > kHapticTriggerCurrentLimit) {
404 trigger_goal_current = kHapticTriggerCurrentLimit;
405 } else if (trigger_goal_current < -kHapticTriggerCurrentLimit) {
406 trigger_goal_current = -kHapticTriggerCurrentLimit;
407 }
408 global_trigger_torque.store(trigger_goal_current,
409 ::std::memory_order_relaxed);
410
411 uint8_t buttons = 0;
412 if (!GPIO_BITBAND(GPIOA_PDIR, 14)) {
413 buttons |= 0x1;
414 }
415 if (!GPIO_BITBAND(GPIOE_PDIR, 26)) {
416 buttons |= 0x2;
417 }
418 if (!GPIO_BITBAND(GPIOC_PDIR, 7)) {
419 buttons |= 0x4;
420 }
421 if (!GPIO_BITBAND(GPIOD_PDIR, 0)) {
422 buttons |= 0x8;
423 }
424
425 float trigger_angle = absolute_trigger_angle;
426
427 // Adjust the trigger range for reporting back.
428 // TODO(austin): We'll likely need to make this symmetric for the controls to
429 // work out well.
430 if (trigger_angle > kTriggerCenter) {
431 trigger_angle = (trigger_angle - kTriggerCenter) / (1.0f - kTriggerCenter);
432 } else {
433 trigger_angle = (trigger_angle - kTriggerCenter) /
434 (kTriggerCenter - kTriggerMaxExtension);
435 }
436
437 // TODO(austin): Class + fns. This is a mess.
438 // TODO(austin): Move this to a separate file. It's too big.
439 int can_trigger = ConvertFloat16(absolute_trigger_angle);
440 int can_trigger_velocity =
441 ConvertFloat16(trigger_observer->X_hat()(1, 0) / 50.0f);
442 int can_trigger_torque =
443 ConvertFloat16(trigger_observer->X_hat()(2, 0) * 2.0f);
444 int can_trigger_current = ConvertFloat14(trigger_goal_current / 10.0f);
445
446 int can_wheel = ConvertFloat16(absolute_wheel_angle);
447 int can_wheel_velocity =
448 ConvertFloat16(wheel_observer->X_hat()(1, 0) / 50.0f);
449 int can_wheel_torque = ConvertFloat16(wheel_observer->X_hat()(2, 0) * 2.0f);
450 int can_wheel_current = ConvertFloat14(wheel_goal_current / 10.0f);
451
452 {
453 const uint8_t trigger_joystick_values[8] = {
454 static_cast<uint8_t>(can_trigger & 0xff),
455 static_cast<uint8_t>((can_trigger >> 8) & 0xff),
456 static_cast<uint8_t>(can_trigger_velocity & 0xff),
457 static_cast<uint8_t>((can_trigger_velocity >> 8) & 0xff),
458 static_cast<uint8_t>(can_trigger_torque & 0xff),
459 static_cast<uint8_t>((can_trigger_torque >> 8) & 0xff),
460 static_cast<uint8_t>(can_trigger_current & 0xff),
461 static_cast<uint8_t>(((buttons & 0x3) << 6) |
462 (can_trigger_current >> 8))};
463 const uint8_t wheel_joystick_values[8] = {
464 static_cast<uint8_t>(can_wheel & 0xff),
465 static_cast<uint8_t>((can_wheel >> 8) & 0xff),
466 static_cast<uint8_t>(can_wheel_velocity & 0xff),
467 static_cast<uint8_t>((can_wheel_velocity >> 8) & 0xff),
468 static_cast<uint8_t>(can_wheel_torque & 0xff),
469 static_cast<uint8_t>((can_wheel_torque >> 8) & 0xff),
470 static_cast<uint8_t>(can_wheel_current & 0xff),
471 static_cast<uint8_t>(((buttons & 0xc) << 4) |
472 (can_wheel_current >> 8))};
473
474 can_send(0, trigger_joystick_values, 8, 2);
475 can_send(1, wheel_joystick_values, 8, 3);
476 }
477
478 ::Eigen::Matrix<float, 1, 1> trigger_U;
479 trigger_U << trigger_goal_current;
480 ::Eigen::Matrix<float, 1, 1> wheel_U;
481 wheel_U << wheel_goal_current;
482 trigger_observer->Predict(trigger_plant, trigger_U,
483 ::std::chrono::milliseconds(1));
484 wheel_observer->Predict(wheel_plant, wheel_U, ::std::chrono::milliseconds(1));
485}
486
487void ConfigurePwmFtm(BigFTM *pwm_ftm) {
488 // Put them all into combine active-high mode, and all the low ones staying
489 // off all the time by default. We'll then use only the low ones.
490 pwm_ftm->C0SC = FTM_CSC_ELSB;
491 pwm_ftm->C0V = 0;
492 pwm_ftm->C1SC = FTM_CSC_ELSB;
493 pwm_ftm->C1V = 0;
494 pwm_ftm->C2SC = FTM_CSC_ELSB;
495 pwm_ftm->C2V = 0;
496 pwm_ftm->C3SC = FTM_CSC_ELSB;
497 pwm_ftm->C3V = 0;
498 pwm_ftm->C4SC = FTM_CSC_ELSB;
499 pwm_ftm->C4V = 0;
500 pwm_ftm->C5SC = FTM_CSC_ELSB;
501 pwm_ftm->C5V = 0;
502 pwm_ftm->C6SC = FTM_CSC_ELSB;
503 pwm_ftm->C6V = 0;
504 pwm_ftm->C7SC = FTM_CSC_ELSB;
505 pwm_ftm->C7V = 0;
506
507 pwm_ftm->COMBINE = FTM_COMBINE_SYNCEN3 /* Synchronize updates usefully */ |
508 FTM_COMBINE_COMP3 /* Make them complementary */ |
509 FTM_COMBINE_COMBINE3 /* Combine the channels */ |
510 FTM_COMBINE_SYNCEN2 /* Synchronize updates usefully */ |
511 FTM_COMBINE_COMP2 /* Make them complementary */ |
512 FTM_COMBINE_COMBINE2 /* Combine the channels */ |
513 FTM_COMBINE_SYNCEN1 /* Synchronize updates usefully */ |
514 FTM_COMBINE_COMP1 /* Make them complementary */ |
515 FTM_COMBINE_COMBINE1 /* Combine the channels */ |
516 FTM_COMBINE_SYNCEN0 /* Synchronize updates usefully */ |
517 FTM_COMBINE_COMP0 /* Make them complementary */ |
518 FTM_COMBINE_COMBINE0 /* Combine the channels */;
519}
520
521bool CountValid(uint32_t count) {
522 static constexpr int kMaxMovement = 1;
523 return count <= kMaxMovement || count >= (4096 - kMaxMovement);
524}
525
526bool ZeroMotors(uint16_t *motor0_offset, uint16_t *motor1_offset,
527 uint16_t *wheel_offset) {
528 static constexpr int kNumberSamples = 1024;
529 static_assert(UINT16_MAX * kNumberSamples <= UINT32_MAX, "Too many samples");
530 uint32_t motor0_sum = 0, motor1_sum = 0, wheel_sum = 0;
531
532 // First clear both encoders.
533 MOTOR0_ENCODER_FTM->CNT = MOTOR1_ENCODER_FTM->CNT = 0;
534 for (int i = 0; i < kNumberSamples; ++i) {
535 delay(1);
536
537 if (!CountValid(MOTOR0_ENCODER_FTM->CNT)) {
538 printf("Motor 0 moved too much\n");
539 return false;
540 }
541 if (!CountValid(MOTOR1_ENCODER_FTM->CNT)) {
542 printf("Motor 1 moved too much\n");
543 return false;
544 }
545
546 DisableInterrupts disable_interrupts;
547 const SmallInitReadings readings = AdcReadSmallInit(disable_interrupts);
548 motor0_sum += readings.motor0_abs;
549 motor1_sum += readings.motor1_abs;
550 wheel_sum += readings.wheel_abs;
551 }
552
553 *motor0_offset = (motor0_sum + kNumberSamples / 2) / kNumberSamples;
554 *motor1_offset = (motor1_sum + kNumberSamples / 2) / kNumberSamples;
555 *wheel_offset = (wheel_sum + kNumberSamples / 2) / kNumberSamples;
556
557 return true;
558}
559
560} // namespace
561
562extern "C" int main() {
563 // for background about this startup delay, please see these conversations
564 // https://forum.pjrc.com/threads/36606-startup-time-(400ms)?p=113980&viewfull=1#post113980
565 // https://forum.pjrc.com/threads/31290-Teensey-3-2-Teensey-Loader-1-24-Issues?p=87273&viewfull=1#post87273
566 delay(400);
567
568 // Set all interrupts to the second-lowest priority to start with.
569 for (int i = 0; i < NVIC_NUM_INTERRUPTS; i++) NVIC_SET_SANE_PRIORITY(i, 0xD);
570
571 // Now set priorities for all the ones we care about. They only have meaning
572 // relative to each other, which means centralizing them here makes it a lot
573 // more manageable.
574 NVIC_SET_SANE_PRIORITY(IRQ_USBOTG, 0x7);
575 NVIC_SET_SANE_PRIORITY(IRQ_FTM0, 0x3);
576 NVIC_SET_SANE_PRIORITY(IRQ_FTM3, 0x3);
577 NVIC_SET_SANE_PRIORITY(IRQ_PIT_CH3, 0x5);
578
579 // Set the LED's pin to output mode.
580 GPIO_BITBAND(GPIOC_PDDR, 5) = 1;
581 PORTC_PCR5 = PORT_PCR_DSE | PORT_PCR_MUX(1);
582
583 // Set up the CAN pins.
584 PORTA_PCR12 = PORT_PCR_DSE | PORT_PCR_MUX(2);
585 PORTA_PCR13 = PORT_PCR_DSE | PORT_PCR_MUX(2);
586
Brian Silvermanff7b3872018-03-10 18:08:30 -0800587 // .1ms filter time.
588 PORTA_DFWR = PORTC_DFWR = PORTD_DFWR = PORTE_DFWR = 6000;
589
Brian Silverman6260c092018-01-14 15:21:36 -0800590 // BTN0
591 PORTC_PCR7 = PORT_PCR_PE | PORT_PCR_PS | PORT_PCR_MUX(1);
Brian Silvermanff7b3872018-03-10 18:08:30 -0800592 PORTC_DFER |= 1 << 7;
Brian Silverman6260c092018-01-14 15:21:36 -0800593 // BTN1
594 PORTE_PCR26 = PORT_PCR_PE | PORT_PCR_PS | PORT_PCR_MUX(1);
Brian Silvermanff7b3872018-03-10 18:08:30 -0800595 PORTE_DFER |= 1 << 26;
Brian Silverman6260c092018-01-14 15:21:36 -0800596 // BTN2
597 PORTA_PCR14 = PORT_PCR_PE | PORT_PCR_PS | PORT_PCR_MUX(1);
Brian Silvermanff7b3872018-03-10 18:08:30 -0800598 PORTA_DFER |= 1 << 14;
Brian Silverman6260c092018-01-14 15:21:36 -0800599 // BTN3
600 PORTD_PCR0 = PORT_PCR_PE | PORT_PCR_PS | PORT_PCR_MUX(1);
Brian Silvermanff7b3872018-03-10 18:08:30 -0800601 PORTD_DFER |= 1 << 0;
602 // BTN4
603 PORTD_PCR7 = PORT_PCR_PE | PORT_PCR_PS | PORT_PCR_MUX(1);
604 PORTD_DFER |= 1 << 7;
605 // BTN5 (only new revision)
606 PORTA_PCR15 = PORT_PCR_PE | PORT_PCR_PS | PORT_PCR_MUX(1);
607 PORTA_DFER |= 1 << 15;
Brian Silverman6260c092018-01-14 15:21:36 -0800608
609 PORTA_PCR5 = PORT_PCR_PE | PORT_PCR_PS | PORT_PCR_MUX(1);
610
611 DMA_CR = DMA_CR_EMLM;
612
613 teensy::UsbDevice usb_device(0, 0x16c0, 0x0490);
614 usb_device.SetManufacturer("FRC 971 Spartan Robotics");
615 usb_device.SetProduct("Pistol Grip Controller debug");
616 teensy::AcmTty tty1(&usb_device);
617 teensy::AcmTty tty2(&usb_device);
618 global_stdout.store(&tty1, ::std::memory_order_release);
619 usb_device.Initialize();
620
621 AdcInitSmall();
622 MathInit();
623 delay(100);
624 can_init(2, 3);
625
626 GPIOD_PCOR = 1 << 3;
627 GPIO_BITBAND(GPIOD_PDDR, 3) = 1;
628 PORTD_PCR3 = PORT_PCR_DSE | PORT_PCR_MUX(1);
629 GPIOD_PSOR = 1 << 3;
630
631 GPIOC_PCOR = 1 << 4;
632 GPIO_BITBAND(GPIOC_PDDR, 4) = 1;
633 PORTC_PCR4 = PORT_PCR_DSE | PORT_PCR_MUX(1);
634 GPIOC_PSOR = 1 << 4;
635
636 LittleMotorControlsImplementation controls0, controls1;
637
638 delay(100);
639
640 // M0_EA = FTM1_QD_PHB
641 PORTB_PCR19 = PORT_PCR_MUX(6);
642 // M0_EB = FTM1_QD_PHA
643 PORTB_PCR18 = PORT_PCR_MUX(6);
644
645 // M1_EA = FTM1_QD_PHA
646 PORTB_PCR0 = PORT_PCR_MUX(6);
647 // M1_EB = FTM1_QD_PHB
648 PORTB_PCR1 = PORT_PCR_MUX(6);
649
650 // M0_CH0 = FTM3_CH4
651 PORTC_PCR8 = PORT_PCR_DSE | PORT_PCR_MUX(3);
652 // M0_CH1 = FTM3_CH2
653 PORTD_PCR2 = PORT_PCR_DSE | PORT_PCR_MUX(4);
654 // M0_CH2 = FTM3_CH6
655 PORTC_PCR10 = PORT_PCR_DSE | PORT_PCR_MUX(3);
656
657 // M1_CH0 = FTM0_CH0
658 PORTC_PCR1 = PORT_PCR_DSE | PORT_PCR_MUX(4);
659 // M1_CH1 = FTM0_CH2
660 PORTC_PCR3 = PORT_PCR_DSE | PORT_PCR_MUX(4);
661 // M1_CH2 = FTM0_CH4
662 PORTD_PCR4 = PORT_PCR_DSE | PORT_PCR_MUX(4);
663
664 Motor motor0(
665 MOTOR0_PWM_FTM, MOTOR0_ENCODER_FTM, &controls0,
666 {&MOTOR0_PWM_FTM->C4V, &MOTOR0_PWM_FTM->C2V, &MOTOR0_PWM_FTM->C6V});
667 motor0.set_debug_tty(&tty2);
668 motor0.set_switching_divisor(kSwitchingDivisor);
669 Motor motor1(
670 MOTOR1_PWM_FTM, MOTOR1_ENCODER_FTM, &controls1,
671 {&MOTOR1_PWM_FTM->C0V, &MOTOR1_PWM_FTM->C2V, &MOTOR1_PWM_FTM->C4V});
672 motor1.set_debug_tty(&tty2);
673 motor1.set_switching_divisor(kSwitchingDivisor);
674 ConfigurePwmFtm(MOTOR0_PWM_FTM);
675 ConfigurePwmFtm(MOTOR1_PWM_FTM);
676 motor0.Init();
677 motor1.Init();
678 global_motor0.store(&motor0, ::std::memory_order_relaxed);
679 global_motor1.store(&motor1, ::std::memory_order_relaxed);
680
681 SIM_SCGC6 |= SIM_SCGC6_PIT;
682 PIT_MCR = 0;
683 PIT_LDVAL3 = BUS_CLOCK_FREQUENCY / 1000;
684 PIT_TCTRL3 = PIT_TCTRL_TIE | PIT_TCTRL_TEN;
685
686 // Have them both wait for the GTB signal.
687 FTM0->CONF = FTM3->CONF =
688 FTM_CONF_GTBEEN | FTM_CONF_NUMTOF(kSwitchingDivisor - 1);
689 // Make FTM3's period half of what it should be so we can get it a half-cycle
690 // out of phase.
691 const uint32_t original_mod = FTM3->MOD;
692 FTM3->MOD = ((original_mod + 1) / 2) - 1;
693 FTM3->SYNC |= FTM_SYNC_SWSYNC;
694
695 // Output triggers to things like the PDBs on initialization.
696 FTM0_EXTTRIG = FTM_EXTTRIG_INITTRIGEN;
697 FTM3_EXTTRIG = FTM_EXTTRIG_INITTRIGEN;
698 // Don't let any memory accesses sneak past here, because we actually
699 // need everything to be starting up.
700 __asm__("" ::: "memory");
701
702 // Give everything a chance to get going.
703 delay(100);
704
705 printf("BSS: %p-%p\n", __bss_ram_start__, __bss_ram_end__);
706 printf("data: %p-%p\n", __data_ram_start__, __data_ram_end__);
707 printf("heap start: %p\n", __heap_start__);
708 printf("stack start: %p\n", __stack_end__);
709
710 printf("Zeroing motors\n");
711 uint16_t motor0_offset, motor1_offset, wheel_offset;
712 while (!ZeroMotors(&motor0_offset, &motor1_offset, &wheel_offset)) {
713 }
714 printf("Done zeroing\n");
715
716 const float motor0_offset_scaled = -analog_ratio(motor0_offset);
717 const float motor1_offset_scaled = analog_ratio(motor1_offset);
718 // Good for the initial trigger.
719 {
720 constexpr float kZeroOffset0 = 0.27f;
721 const int motor0_starting_point = static_cast<int>(
722 (motor0_offset_scaled + (kZeroOffset0 / 7.0f)) * 4096.0f);
723 printf("Motor 0 starting at %d\n", motor0_starting_point);
724 motor0.set_encoder_calibration_offset(motor0_starting_point);
725 motor0.set_encoder_multiplier(-1);
726
727 // Calibrate neutral here.
728 motor0.set_encoder_offset(motor0.encoder_offset() - 2065 + 20);
729
730 uint32_t new_encoder = motor0.wrapped_encoder();
731 int32_t absolute_encoder = motor0.absolute_encoder(new_encoder);
732 printf("Motor 0 encoder %d absolute %d\n", static_cast<int>(new_encoder),
733 static_cast<int>(absolute_encoder));
734 }
735
736 {
737 constexpr float kZeroOffset1 = 0.26f;
738 const int motor1_starting_point = static_cast<int>(
739 (motor1_offset_scaled + (kZeroOffset1 / 7.0f)) * 4096.0f);
740 printf("Motor 1 starting at %d\n", motor1_starting_point);
741 motor1.set_encoder_calibration_offset(motor1_starting_point);
742 motor1.set_encoder_multiplier(-1);
743
744 float wheel_position = absolute_wheel(analog_ratio(wheel_offset));
745
746 uint32_t encoder = motor1.wrapped_encoder();
747
748 printf("Wheel starting at %d, encoder %" PRId32 "\n",
749 static_cast<int>(wheel_position * 1000.0f), encoder);
750
751 constexpr float kWheelGearRatio = (1.25f + 0.02f) / 0.35f;
752 constexpr float kWrappedWheelAtZero = 0.6586310546875f;
753
754 const int encoder_wraps =
755 static_cast<int>(lround(wheel_position * kWheelGearRatio -
756 (encoder / 4096.f) + kWrappedWheelAtZero));
757
758 printf("Wraps: %d\n", encoder_wraps);
759 motor1.set_encoder_offset(4096 * encoder_wraps + motor1.encoder_offset() -
760 static_cast<int>(kWrappedWheelAtZero * 4096));
761 printf("Wheel encoder now at %d\n",
762 static_cast<int>(1000.f / 4096.f *
763 motor1.absolute_encoder(motor1.wrapped_encoder())));
764 }
765
766 // Turn an LED on for Austin.
767 GPIO_BITBAND(GPIOC_PDDR, 6) = 1;
768 GPIOC_PCOR = 1 << 6;
769 PORTC_PCR6 = PORT_PCR_DSE | PORT_PCR_MUX(1);
770
771 // M0_THW
772 PORTC_PCR11 = PORT_PCR_PE | PORT_PCR_PS | PORT_PCR_MUX(1);
773 // M0_FAULT
774 PORTD_PCR6 = PORT_PCR_PE | PORT_PCR_PS | PORT_PCR_MUX(1);
775 // M1_THW
776 PORTC_PCR2 = PORT_PCR_PE | PORT_PCR_PS | PORT_PCR_MUX(1);
777 // M1_FAULT
778 PORTD_PCR5 = PORT_PCR_PE | PORT_PCR_PS | PORT_PCR_MUX(1);
779
780 motor0.Start();
781 motor1.Start();
782 {
783 // We rely on various things happening faster than the timer period, so make
784 // sure slow USB or whatever interrupts don't prevent that.
785 DisableInterrupts disable_interrupts;
786
787 // First clear the overflow flag.
788 FTM3->SC &= ~FTM_SC_TOF;
789
790 // Now poke the GTB to actually start both timers.
791 FTM0->CONF = FTM_CONF_GTBEEN | FTM_CONF_GTBEOUT |
792 FTM_CONF_NUMTOF(kSwitchingDivisor - 1);
793
794 // Wait for it to overflow twice. For some reason, just once doesn't work.
795 while (!(FTM3->SC & FTM_SC_TOF)) {
796 }
797 FTM3->SC &= ~FTM_SC_TOF;
798 while (!(FTM3->SC & FTM_SC_TOF)) {
799 }
800
801 // Now put the MOD value back to what it was.
802 FTM3->MOD = original_mod;
803 FTM3->PWMLOAD = FTM_PWMLOAD_LDOK;
804
805 // And then clear the overflow flags before enabling interrupts so we
806 // actually wait until the next overflow to start doing interrupts.
807 FTM0->SC &= ~FTM_SC_TOF;
808 FTM3->SC &= ~FTM_SC_TOF;
809 NVIC_ENABLE_IRQ(IRQ_FTM0);
810 NVIC_ENABLE_IRQ(IRQ_FTM3);
811 }
812 global_trigger_plant.store(
813 new StateFeedbackPlant<3, 1, 1, float>(MakeIntegralHapticTriggerPlant()));
814 global_trigger_observer.store(new StateFeedbackObserver<3, 1, 1, float>(
815 MakeIntegralHapticTriggerObserver()));
816 global_trigger_observer.load(::std::memory_order_relaxed)
817 ->Reset(global_trigger_plant.load(::std::memory_order_relaxed));
818
819 global_wheel_plant.store(
820 new StateFeedbackPlant<3, 1, 1, float>(MakeIntegralHapticWheelPlant()));
821 global_wheel_observer.store(new StateFeedbackObserver<3, 1, 1, float>(
822 MakeIntegralHapticWheelObserver()));
823 global_wheel_observer.load(::std::memory_order_relaxed)
824 ->Reset(global_wheel_plant.load(::std::memory_order_relaxed));
825
826 delay(1000);
827
828 NVIC_ENABLE_IRQ(IRQ_PIT_CH3);
829
830 // TODO(Brian): Use SLEEPONEXIT to reduce interrupt latency?
831 while (true) {
832 if (!GPIO_BITBAND(GPIOC_PDIR, 11)) {
833 if (!GPIO_BITBAND(GPIOC_PDOR, 5)) {
834 printf("M0_THW\n");
835 }
836 GPIOC_PSOR = 1 << 5;
837 }
838 if (!GPIO_BITBAND(GPIOD_PDIR, 6)) {
839 if (!GPIO_BITBAND(GPIOC_PDOR, 5)) {
840 printf("M0_FAULT\n");
841 }
842 GPIOC_PSOR = 1 << 5;
843 }
844 if (!GPIO_BITBAND(GPIOC_PDIR, 2)) {
845 if (!GPIO_BITBAND(GPIOC_PDOR, 5)) {
846 printf("M1_THW\n");
847 }
848 GPIOC_PSOR = 1 << 5;
849 }
850 if (!GPIO_BITBAND(GPIOD_PDIR, 5)) {
851 if (!GPIO_BITBAND(GPIOC_PDOR, 5)) {
852 printf("M1_FAULT\n");
853 }
854 GPIOC_PSOR = 1 << 5;
855 }
856 }
857
858 return 0;
859}
860
861} // namespace salsa
862} // namespace frc971