Tyler Chatow | 37ecdcd | 2019-01-26 20:18:42 -0800 | [diff] [blame] | 1 | #ifndef Y2019_CONSTANTS_H_ |
| 2 | #define Y2019_CONSTANTS_H_ |
| 3 | |
James Kuszmaul | 22c5ab3 | 2019-02-09 14:45:58 -0800 | [diff] [blame] | 4 | #include <array> |
Tyler Chatow | bf0609c | 2021-07-31 16:13:27 -0700 | [diff] [blame^] | 5 | #include <cmath> |
| 6 | #include <cstdint> |
Tyler Chatow | 37ecdcd | 2019-01-26 20:18:42 -0800 | [diff] [blame] | 7 | |
| 8 | #include "frc971/constants.h" |
James Kuszmaul | f4ede20 | 2020-02-14 08:47:40 -0800 | [diff] [blame] | 9 | #include "frc971/control_loops/drivetrain/camera.h" |
Tyler Chatow | bf0609c | 2021-07-31 16:13:27 -0700 | [diff] [blame^] | 10 | #include "frc971/control_loops/pose.h" |
Theo Bafrali | 00e4227 | 2019-02-12 01:07:46 -0800 | [diff] [blame] | 11 | #include "frc971/control_loops/static_zeroing_single_dof_profiled_subsystem.h" |
Sabina Davis | 7be49f3 | 2019-02-02 00:30:19 -0800 | [diff] [blame] | 12 | #include "y2019/control_loops/drivetrain/drivetrain_dog_motor_plant.h" |
Alex Perry | 5fb5ff2 | 2019-02-09 21:53:17 -0800 | [diff] [blame] | 13 | #include "y2019/control_loops/superstructure/elevator/elevator_plant.h" |
Theo Bafrali | 00e4227 | 2019-02-12 01:07:46 -0800 | [diff] [blame] | 14 | #include "y2019/control_loops/superstructure/intake/intake_plant.h" |
Alex Perry | 5fb5ff2 | 2019-02-09 21:53:17 -0800 | [diff] [blame] | 15 | #include "y2019/control_loops/superstructure/stilts/stilts_plant.h" |
| 16 | #include "y2019/control_loops/superstructure/wrist/wrist_plant.h" |
Tyler Chatow | 37ecdcd | 2019-01-26 20:18:42 -0800 | [diff] [blame] | 17 | |
| 18 | namespace y2019 { |
| 19 | namespace constants { |
| 20 | |
| 21 | // Has all of our "constants", except the ones that come from other places. The |
| 22 | // ones which change between robots are put together with a workable way to |
| 23 | // retrieve the values for the current robot. |
| 24 | |
| 25 | // Everything is in SI units (volts, radians, meters, seconds, etc). |
| 26 | // Some of these values are related to the conversion between raw values |
| 27 | // (encoder counts, voltage, etc) to scaled units (radians, meters, etc). |
| 28 | // |
| 29 | // All ratios are from the encoder shaft to the output units. |
| 30 | |
James Kuszmaul | 22c5ab3 | 2019-02-09 14:45:58 -0800 | [diff] [blame] | 31 | class Field { |
| 32 | public: |
| 33 | typedef ::frc971::control_loops::TypedPose<double> Pose; |
James Kuszmaul | f4ede20 | 2020-02-14 08:47:40 -0800 | [diff] [blame] | 34 | typedef ::frc971::control_loops::TypedTarget<double> Target; |
James Kuszmaul | 22c5ab3 | 2019-02-09 14:45:58 -0800 | [diff] [blame] | 35 | typedef ::frc971::control_loops::TypedLineSegment<double> Obstacle; |
| 36 | |
| 37 | static constexpr size_t kNumTargets = 32; |
| 38 | static constexpr size_t kNumObstacles = 10; |
| 39 | |
| 40 | Field(); |
| 41 | |
| 42 | ::std::array<Target, kNumTargets> targets() const { return targets_; } |
| 43 | ::std::array<Obstacle, kNumObstacles> obstacles() const { return obstacles_; } |
| 44 | |
| 45 | private: |
| 46 | // All target locations are defined as being at the center of the target, |
| 47 | // except for the height, for which we use the top of the target. |
| 48 | ::std::array<Target, kNumTargets> targets_; |
| 49 | // Obstacle locations are approximate, as we are just trying to roughly |
| 50 | // approximate what will block our view when on the field. |
| 51 | // If anything, we should err on the side of making obstacles too small so |
| 52 | // that if there is any error in our position, we don't assume that it must |
| 53 | // be hidden behind a target when it really is not. |
| 54 | ::std::array<Obstacle, kNumObstacles> obstacles_; |
| 55 | }; |
| 56 | |
Tyler Chatow | 37ecdcd | 2019-01-26 20:18:42 -0800 | [diff] [blame] | 57 | struct Values { |
| 58 | static const int kZeroingSampleSize = 200; |
Sabina Davis | 7be49f3 | 2019-02-02 00:30:19 -0800 | [diff] [blame] | 59 | |
Theo Bafrali | 00e4227 | 2019-02-12 01:07:46 -0800 | [diff] [blame] | 60 | // Drivetrain Constants |
Sabina Davis | 7be49f3 | 2019-02-02 00:30:19 -0800 | [diff] [blame] | 61 | static constexpr double kDrivetrainCyclesPerRevolution() { return 512.0; } |
| 62 | static constexpr double kDrivetrainEncoderCountsPerRevolution() { |
| 63 | return kDrivetrainCyclesPerRevolution() * 4; |
| 64 | } |
Alex Perry | 5fb5ff2 | 2019-02-09 21:53:17 -0800 | [diff] [blame] | 65 | static constexpr double kDrivetrainEncoderRatio() { return (24.0 / 52.0); } |
Sabina Davis | 7be49f3 | 2019-02-02 00:30:19 -0800 | [diff] [blame] | 66 | static constexpr double kMaxDrivetrainEncoderPulsesPerSecond() { |
| 67 | return control_loops::drivetrain::kFreeSpeed / (2.0 * M_PI) * |
| 68 | control_loops::drivetrain::kHighOutputRatio / |
| 69 | constants::Values::kDrivetrainEncoderRatio() * |
| 70 | kDrivetrainEncoderCountsPerRevolution(); |
| 71 | } |
Alex Perry | 5fb5ff2 | 2019-02-09 21:53:17 -0800 | [diff] [blame] | 72 | |
| 73 | // Elevator |
| 74 | static constexpr double kElevatorEncoderCountsPerRevolution() { |
| 75 | return 4096.0; |
| 76 | } |
| 77 | |
| 78 | static constexpr double kElevatorEncoderRatio() { |
| 79 | return (1.0) * control_loops::superstructure::elevator::kRadius; |
| 80 | } |
| 81 | |
| 82 | static constexpr double kMaxElevatorEncoderPulsesPerSecond() { |
| 83 | return control_loops::superstructure::elevator::kFreeSpeed * |
| 84 | control_loops::superstructure::elevator::kOutputRatio / |
| 85 | kElevatorEncoderRatio() / (2.0 * M_PI) * |
| 86 | kElevatorEncoderCountsPerRevolution(); |
| 87 | } |
| 88 | |
| 89 | static constexpr double kElevatorPotRatio() { |
| 90 | return (1.0) * control_loops::superstructure::elevator::kRadius; |
| 91 | } |
| 92 | |
Austin Schuh | 7c473cb | 2019-02-10 14:49:19 -0800 | [diff] [blame] | 93 | static constexpr ::frc971::constants::Range kElevatorRange() { |
| 94 | return ::frc971::constants::Range{ |
Austin Schuh | dc9050b | 2019-02-22 20:45:12 -0800 | [diff] [blame] | 95 | -0.02, // Bottom Hard |
Austin Schuh | ed7f863 | 2019-02-15 23:12:20 -0800 | [diff] [blame] | 96 | 1.62, // Top Hard |
| 97 | 0.01, // Bottom Soft |
| 98 | 1.59 // Top Soft |
Austin Schuh | 7c473cb | 2019-02-10 14:49:19 -0800 | [diff] [blame] | 99 | }; |
| 100 | } |
| 101 | |
Alex Perry | 5fb5ff2 | 2019-02-09 21:53:17 -0800 | [diff] [blame] | 102 | // Intake |
| 103 | static constexpr double kIntakeEncoderCountsPerRevolution() { return 4096.0; } |
| 104 | |
| 105 | static constexpr double kIntakeEncoderRatio() { return (18.0 / 38.0); } |
| 106 | |
| 107 | static constexpr double kMaxIntakeEncoderPulsesPerSecond() { |
| 108 | return control_loops::superstructure::intake::kFreeSpeed * |
| 109 | control_loops::superstructure::intake::kOutputRatio / |
| 110 | kIntakeEncoderRatio() / (2.0 * M_PI) * |
| 111 | kIntakeEncoderCountsPerRevolution(); |
| 112 | } |
| 113 | |
Austin Schuh | 7c473cb | 2019-02-10 14:49:19 -0800 | [diff] [blame] | 114 | static constexpr ::frc971::constants::Range kIntakeRange() { |
| 115 | return ::frc971::constants::Range{ |
Austin Schuh | ed7f863 | 2019-02-15 23:12:20 -0800 | [diff] [blame] | 116 | -1.30, // Back Hard |
| 117 | 1.35, // Front Hard |
| 118 | -1.25, // Back Soft |
| 119 | 1.30 // Front Soft |
Austin Schuh | 7c473cb | 2019-02-10 14:49:19 -0800 | [diff] [blame] | 120 | }; |
| 121 | } |
| 122 | |
Alex Perry | 5fb5ff2 | 2019-02-09 21:53:17 -0800 | [diff] [blame] | 123 | // Wrist |
| 124 | static constexpr double kWristEncoderCountsPerRevolution() { return 4096.0; } |
| 125 | |
| 126 | static constexpr double kWristEncoderRatio() { |
| 127 | return (20.0 / 100.0) * (24.0 / 84.0); |
| 128 | } |
| 129 | |
| 130 | static constexpr double kMaxWristEncoderPulsesPerSecond() { |
| 131 | return control_loops::superstructure::wrist::kFreeSpeed * |
| 132 | control_loops::superstructure::wrist::kOutputRatio / |
| 133 | kWristEncoderRatio() / (2.0 * M_PI) * |
| 134 | kWristEncoderCountsPerRevolution(); |
| 135 | } |
| 136 | |
| 137 | static constexpr double kWristPotRatio() { return (24.0) / (84.0); } |
| 138 | |
Austin Schuh | 7c473cb | 2019-02-10 14:49:19 -0800 | [diff] [blame] | 139 | static constexpr ::frc971::constants::Range kWristRange() { |
| 140 | return ::frc971::constants::Range{ |
| 141 | -3.14, // Back Hard |
Austin Schuh | ed7f863 | 2019-02-15 23:12:20 -0800 | [diff] [blame] | 142 | 3.14, // Front Hard |
Austin Schuh | 7c473cb | 2019-02-10 14:49:19 -0800 | [diff] [blame] | 143 | -2.97, // Back Soft |
| 144 | 2.41 // Front Soft |
| 145 | }; |
| 146 | } |
| 147 | |
Alex Perry | 5fb5ff2 | 2019-02-09 21:53:17 -0800 | [diff] [blame] | 148 | // Stilts |
| 149 | static constexpr double kStiltsEncoderCountsPerRevolution() { return 4096.0; } |
| 150 | |
Theo Bafrali | 00e4227 | 2019-02-12 01:07:46 -0800 | [diff] [blame] | 151 | // Stilts Constants |
Alex Perry | 5fb5ff2 | 2019-02-09 21:53:17 -0800 | [diff] [blame] | 152 | static constexpr double kStiltsEncoderRatio() { |
| 153 | return (1.0 /* Gear ratio */) * |
| 154 | control_loops::superstructure::stilts::kRadius; |
| 155 | } |
| 156 | |
| 157 | static constexpr double kMaxStiltsEncoderPulsesPerSecond() { |
| 158 | return control_loops::superstructure::stilts::kFreeSpeed * |
| 159 | control_loops::superstructure::stilts::kOutputRatio / |
| 160 | kStiltsEncoderRatio() / (2.0 * M_PI) * |
| 161 | kStiltsEncoderCountsPerRevolution(); |
| 162 | } |
| 163 | |
| 164 | static constexpr double kStiltsPotRatio() { |
| 165 | return (1.0 /* Gear ratio */) * |
| 166 | control_loops::superstructure::stilts::kRadius; |
| 167 | } |
| 168 | |
Austin Schuh | 7c473cb | 2019-02-10 14:49:19 -0800 | [diff] [blame] | 169 | static constexpr ::frc971::constants::Range kStiltsRange() { |
| 170 | return ::frc971::constants::Range{ |
Austin Schuh | ed7f863 | 2019-02-15 23:12:20 -0800 | [diff] [blame] | 171 | -0.01, // Top Hard |
| 172 | 0.72, // Bottom Hard |
| 173 | 0.00, // Top Soft |
| 174 | 0.71 // Bottom Soft |
Austin Schuh | 7c473cb | 2019-02-10 14:49:19 -0800 | [diff] [blame] | 175 | }; |
| 176 | } |
| 177 | |
Alex Perry | 5fb5ff2 | 2019-02-09 21:53:17 -0800 | [diff] [blame] | 178 | struct PotAndAbsConstants { |
Theo Bafrali | 00e4227 | 2019-02-12 01:07:46 -0800 | [diff] [blame] | 179 | ::frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemParams< |
| 180 | ::frc971::zeroing::PotAndAbsoluteEncoderZeroingEstimator> |
| 181 | subsystem_params; |
Alex Perry | 5fb5ff2 | 2019-02-09 21:53:17 -0800 | [diff] [blame] | 182 | double potentiometer_offset; |
| 183 | }; |
Theo Bafrali | 00e4227 | 2019-02-12 01:07:46 -0800 | [diff] [blame] | 184 | |
Alex Perry | 5fb5ff2 | 2019-02-09 21:53:17 -0800 | [diff] [blame] | 185 | PotAndAbsConstants elevator; |
| 186 | PotAndAbsConstants wrist; |
Theo Bafrali | 00e4227 | 2019-02-12 01:07:46 -0800 | [diff] [blame] | 187 | ::frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemParams< |
| 188 | ::frc971::zeroing::AbsoluteEncoderZeroingEstimator> |
| 189 | intake; |
Alex Perry | 5fb5ff2 | 2019-02-09 21:53:17 -0800 | [diff] [blame] | 190 | |
Theo Bafrali | 00e4227 | 2019-02-12 01:07:46 -0800 | [diff] [blame] | 191 | PotAndAbsConstants stilts; |
James Kuszmaul | 09f564a | 2019-02-18 17:37:09 -0800 | [diff] [blame] | 192 | |
| 193 | struct CameraCalibration { |
James Kuszmaul | 09f564a | 2019-02-18 17:37:09 -0800 | [diff] [blame] | 194 | // Pose of the camera relative to the robot. |
| 195 | ::frc971::control_loops::TypedPose<double> pose; |
| 196 | // Field of view, in radians. This is total horizontal FOV, from left |
| 197 | // edge to right edge of the camera image. |
| 198 | double fov; |
| 199 | }; |
| 200 | |
| 201 | static constexpr size_t kNumCameras = 5; |
| 202 | ::std::array<CameraCalibration, kNumCameras> cameras; |
James Kuszmaul | f4ede20 | 2020-02-14 08:47:40 -0800 | [diff] [blame] | 203 | frc971::control_loops::TypedCamera<Field::kNumTargets, Field::kNumObstacles, |
| 204 | double>::NoiseParameters |
| 205 | camera_noise_parameters; |
Tyler Chatow | 37ecdcd | 2019-01-26 20:18:42 -0800 | [diff] [blame] | 206 | }; |
| 207 | |
| 208 | // Creates (once) a Values instance for ::aos::network::GetTeamNumber() and |
| 209 | // returns a reference to it. |
| 210 | const Values &GetValues(); |
| 211 | |
| 212 | // Creates Values instances for each team number it is called with and returns |
| 213 | // them. |
| 214 | const Values &GetValuesForTeam(uint16_t team_number); |
| 215 | |
| 216 | } // namespace constants |
| 217 | } // namespace y2019 |
| 218 | |
| 219 | #endif // Y2019_CONSTANTS_H_ |