|
4 | 4 |
|
5 | 5 | #include "AlphaArm.h"
|
6 | 6 |
|
7 |
| -// fiddle with these values |
8 |
| -AlphaArm::AlphaArm(AlphaArmConfig config) |
9 |
| - : _config(config), |
10 |
| - _pidWom(_config.path + "/pid", |
11 |
| - config.pidConfigA) /*_table(nt::NetworkTableInstance::GetDefault().GetTable(config.path)*/ {} |
| 7 | +AlphaArm::AlphaArm(AlphaArmConfig config) : _config(config) {} |
12 | 8 |
|
13 |
| -void AlphaArm::OnStart() { |
14 |
| - started = false; |
15 |
| - // _pidWom.Reset(); |
16 |
| - // _pidWom.SetSetpoint(_config.alphaArmGearbox.encoder->GetEncoderPosition()); |
| 9 | +AlphaArmConfig AlphaArm::GetConfig() { |
| 10 | + return _config; |
17 | 11 | }
|
18 | 12 |
|
19 | 13 | void AlphaArm::OnUpdate(units::second_t dt) {
|
20 |
| - _table->GetEntry("Error").SetDouble(_pidWom.GetError().value()); |
21 |
| - _table->GetEntry("Current Pos").SetDouble(_config.alphaArmGearbox.encoder->GetEncoderPosition().value()); |
22 |
| - _table->GetEntry("Setpoint").SetDouble(_pidWom.GetSetpoint().value()); |
23 |
| - _table->GetEntry("State ").SetString(_stateName); |
24 | 14 | switch (_state) {
|
25 | 15 | case AlphaArmState::kIdle:
|
26 |
| - _stateName = "Idle"; |
27 |
| - // _pidWom.SetSetpoint(_config.alphaArmGearbox.encoder->GetEncoderPosition()); |
28 | 16 |
|
| 17 | + // _config.alphaArmGearbox.motorController->SetVoltage(0_V); |
| 18 | + // _config.wristGearbox.motorController->SetVoltage(0_V); |
29 | 19 | _setAlphaArmVoltage = 0_V;
|
| 20 | + _setWristVoltage = 0_V; |
30 | 21 |
|
31 | 22 | break;
|
32 | 23 | case AlphaArmState::kRaw:
|
33 |
| - _stateName = "Raw"; |
34 |
| - |
35 | 24 | _setAlphaArmVoltage = _rawArmVoltage;
|
| 25 | + _setWristVoltage = _rawWristVoltage; |
| 26 | + _config.alphaArmGearbox.motorController->SetVoltage(_rawArmVoltage); |
| 27 | + _config.wristGearbox.motorController->SetVoltage(_rawWristVoltage); |
36 | 28 |
|
37 | 29 | break;
|
38 |
| - case AlphaArmState::kAmpAngle: { |
39 |
| - _stateName = "Amp Angle"; |
40 |
| - |
41 |
| - // _pidWom.SetSetpoint(_goal); |
42 |
| - // _setAlphaArmVoltage = _pidWom.Calculate(_config.alphaArmGearbox.encoder->GetEncoderPosition(), dt, |
43 |
| - // 0_V); |
| 30 | + case AlphaArmState::kForwardWrist: |
| 31 | + _config.wristGearbox.motorController->SetVoltage(3_V); |
| 32 | + _setWristVoltage = 3_V; |
44 | 33 |
|
45 |
| - if (started) { |
46 |
| - if (_controlledRawVoltage.value() == 0) { |
47 |
| - if (-_config.alphaArmGearbox.encoder->GetEncoderPosition() > (_startingPos + (3.1415_rad / 2))) { |
48 |
| - // _pidWom.SetSetpoint(_encoderSetpoint); |
49 |
| - // _setAlphaArmVoltage = |
50 |
| - // -_pidWom.Calculate(-_config.alphaArmGearbox.encoder->GetEncoderPosition(), dt, 0.0_V); |
51 |
| - // _table->GetEntry("Demand").SetDouble(_setAlphaArmVoltage.value()); |
52 |
| - // } else if (_config.alphaArmGearbox.encoder->GetEncoderPosition() < 0_rad) { |
53 |
| - // _pidWom.SetSetpoint(_encoderSetpoint); |
54 |
| - // _setAlphaArmVoltage = |
55 |
| - // _pidWom.Calculate(_config.alphaArmGearbox.encoder->GetEncoderPosition(), dt, 0.0_V); |
56 |
| - // _table->GetEntry("Demand").SetDouble(_setAlphaArmVoltage.value()); |
57 |
| - _setAlphaArmVoltage = 0_V; |
58 |
| - } else { |
59 |
| - _pidWom.SetSetpoint(_encoderSetpoint); |
60 |
| - _setAlphaArmVoltage = |
61 |
| - -_pidWom.Calculate(-_config.alphaArmGearbox.encoder->GetEncoderPosition(), dt, 0.0_V); |
62 |
| - // _pidWom.Reset(); |
63 |
| - // _encoderSetpoint = _config.alphaArmGearbox.encoder->GetEncoderPosition(); |
64 |
| - // _setAlphaArmVoltage = _controlledRawVoltage; |
65 |
| - } |
66 |
| - } else { |
67 |
| - _pidWom.Reset(); |
68 |
| - _encoderSetpoint = -_config.alphaArmGearbox.encoder->GetEncoderPosition(); |
69 |
| - _setAlphaArmVoltage = _controlledRawVoltage; |
70 |
| - } |
71 |
| - } else { |
72 |
| - _pidWom.Reset(); |
73 |
| - _encoderSetpoint = -_config.alphaArmGearbox.encoder->GetEncoderPosition(); |
74 |
| - _setAlphaArmVoltage = _controlledRawVoltage; |
75 |
| - |
76 |
| - if (std::abs(_controlledRawVoltage.value()) > 0) { |
77 |
| - _startingPos = -_config.alphaArmGearbox.encoder->GetEncoderPosition(); |
78 |
| - started = true; |
79 |
| - } |
80 |
| - } |
81 |
| - } break; |
82 |
| - case AlphaArmState::kSpeakerAngle: |
83 |
| - _stateName = "Speaker Angle"; |
84 |
| - // _pidWom.SetSetpoint(_goal); |
85 |
| - // _setAlphaArmVoltage = _pidWom.Calculate(_config.alphaArmGearbox.encoder->GetEncoderPosition(), dt, |
86 |
| - // 0_V); |
87 |
| - break; |
88 |
| - case AlphaArmState::kStowed: |
89 |
| - _stateName = "Stowed"; |
90 |
| - // _pidWom.SetSetpoint(_goal); |
91 |
| - // _setAlphaArmVoltage = _pidWom.Calculate(_config.alphaArmGearbox.encoder->GetEncoderPosition(), dt, |
92 |
| - // 0_V); |
93 |
| - break; |
| 34 | + case AlphaArmState::kReverseWrist: |
| 35 | + _config.wristGearbox.motorController->SetVoltage(-3_V); |
| 36 | + _setWristVoltage = -3_V; |
94 | 37 | default:
|
95 |
| - _stateName = "Error"; |
96 | 38 | std::cout << "oops, wrong state" << std::endl;
|
97 | 39 | break;
|
98 | 40 | }
|
99 |
| - std::cout << " ARM POSITION: " << _config.alphaArmGearbox.encoder->GetEncoderPosition().value() |
100 |
| - << std::endl; |
101 |
| - // std::cout << "OUTPUT VOLTAGE: " << _setAlphaArmVoltage.value() << std::endl; |
| 41 | + // transmission translate |
| 42 | + // _config.armGearBox.motorController->SetVoltage(setAlphaArmVoltage); |
| 43 | + // _config.alphaArmGearbox.motorController->SetVoltage(setAlphaArmVoltage); |
| 44 | + // _config.wristGearbox.motorController->SetVoltage(setWristVoltage); |
102 | 45 | _config.alphaArmGearbox.motorController->SetVoltage(_setAlphaArmVoltage);
|
| 46 | + _config.wristGearbox.motorController->SetVoltage(_setWristVoltage); |
| 47 | + |
| 48 | + // _config.wristGearbox.motorController->SetVoltage(_setVoltage); |
103 | 49 | }
|
104 | 50 |
|
105 | 51 | void AlphaArm::SetState(AlphaArmState state) {
|
106 | 52 | _state = state;
|
107 | 53 | }
|
108 | 54 |
|
109 |
| -void AlphaArm::SetGoal(units::radian_t goal) { |
110 |
| - _goal = goal; |
111 |
| -} |
| 55 | +// void AlphaArm::SetRaw(units::volt_t voltage){ |
| 56 | +// _rawArmVoltage = voltage; |
| 57 | +// _rawWristVoltage = voltage; |
| 58 | +// } |
112 | 59 |
|
113 | 60 | void AlphaArm::SetArmRaw(units::volt_t voltage) {
|
114 |
| - std::cout << "VOLTAGE: " << voltage.value() << std::endl; |
115 | 61 | _rawArmVoltage = voltage;
|
116 | 62 | }
|
117 | 63 |
|
118 |
| -void AlphaArm::setControllerRaw(units::volt_t voltage) { |
119 |
| - _controlledRawVoltage = voltage; |
| 64 | +void AlphaArm::setWristRaw(units::volt_t voltage) { |
| 65 | + _rawWristVoltage = voltage; |
120 | 66 | }
|
0 commit comments