blob: 56a5aa13b7feb9057cc91098b938c844c75f40fd [file] [log] [blame]
Comran Morshed41ed7c22015-11-04 21:03:37 +00001#include <stdio.h>
2#include <string.h>
3#include <unistd.h>
4#include <inttypes.h>
5
6#include <thread>
7#include <mutex>
8#include <functional>
9
10#include "Encoder.h"
11#include "Talon.h"
12#include "DriverStation.h"
13#include "AnalogInput.h"
14#include "Compressor.h"
15#include "Relay.h"
16#include "RobotBase.h"
17#include "dma.h"
Comran Morshed41ed7c22015-11-04 21:03:37 +000018#include "DigitalInput.h"
Brian Silvermanc7e8fdd2015-12-06 02:48:27 -050019#include "PowerDistributionPanel.h"
Austin Schuhbc9a2ab2015-11-26 16:20:17 -080020#undef ERROR
Comran Morshed41ed7c22015-11-04 21:03:37 +000021
22#include "aos/common/logging/logging.h"
23#include "aos/common/logging/queue_logging.h"
24#include "aos/common/time.h"
25#include "aos/common/util/log_interval.h"
26#include "aos/common/util/phased_loop.h"
27#include "aos/common/util/wrapping_counter.h"
28#include "aos/common/stl_mutex.h"
29#include "aos/linux_code/init.h"
30#include "aos/common/messages/robot_state.q.h"
31
32#include "y2014_bot3/control_loops/drivetrain/drivetrain.q.h"
33#include "y2014_bot3/control_loops/rollers/rollers.q.h"
34#include "y2014_bot3/autonomous/auto.q.h"
Brian Silverman811f8ec2015-12-06 01:29:42 -050035#include "y2014_bot3/control_loops/drivetrain/drivetrain.h"
36#include "y2014_bot3/control_loops/rollers/rollers.h"
Comran Morshed41ed7c22015-11-04 21:03:37 +000037
38#include "frc971/wpilib/joystick_sender.h"
39#include "frc971/wpilib/loop_output_handler.h"
40#include "frc971/wpilib/buffered_solenoid.h"
41#include "frc971/wpilib/buffered_pcm.h"
42#include "frc971/wpilib/gyro_sender.h"
43#include "frc971/wpilib/logging.q.h"
Brian Silverman811f8ec2015-12-06 01:29:42 -050044#include "frc971/wpilib/wpilib_interface.h"
Comran Morshed41ed7c22015-11-04 21:03:37 +000045
46#ifndef M_PI
47#define M_PI 3.14159265358979323846
48#endif
49
50using ::aos::util::SimpleLogInterval;
51using ::y2014_bot3::control_loops::drivetrain_queue;
52using ::y2014_bot3::control_loops::rollers_queue;
53using ::frc971::wpilib::BufferedPcm;
54using ::frc971::wpilib::BufferedSolenoid;
55using ::frc971::wpilib::LoopOutputHandler;
56using ::frc971::wpilib::JoystickSender;
57using ::frc971::wpilib::GyroSender;
58
59namespace frc971 {
60namespace wpilib {
61
62double drivetrain_translate(int32_t in) {
63 return static_cast<double>(in) / (256.0 /*cpr*/ * 4.0 /*4x*/) *
64 ::y2014_bot3::control_loops::kDrivetrainEncoderRatio *
65 (4 /*wheel diameter*/ * 2.54 / 100.0 * M_PI);
66}
67
Brian Silverman51091a02015-12-26 15:56:58 -080068double drivetrain_velocity_translate(double in) {
69 return (1.0 / in) / 256.0 /*cpr*/ *
70 ::y2014_bot3::control_loops::kDrivetrainEncoderRatio *
71 (4 /*wheel diameter*/ * 2.54 / 100.0 * M_PI);
72}
73
Comran Morshed41ed7c22015-11-04 21:03:37 +000074// Reads in our inputs. (sensors, voltages, etc.)
75class SensorReader {
76 public:
77 SensorReader() {}
78
79 void set_drivetrain_left_encoder(::std::unique_ptr<Encoder> encoder) {
80 drivetrain_left_encoder_ = ::std::move(encoder);
Brian Silverman51091a02015-12-26 15:56:58 -080081 drivetrain_left_encoder_->SetMaxPeriod(0.005);
Comran Morshed41ed7c22015-11-04 21:03:37 +000082 }
83
84 void set_drivetrain_right_encoder(::std::unique_ptr<Encoder> encoder) {
85 drivetrain_right_encoder_ = ::std::move(encoder);
Brian Silverman51091a02015-12-26 15:56:58 -080086 drivetrain_right_encoder_->SetMaxPeriod(0.005);
Comran Morshed41ed7c22015-11-04 21:03:37 +000087 }
88
89 void operator()() {
90 ::aos::SetCurrentThreadName("SensorReader");
91 LOG(INFO, "In sensor reader thread\n");
92
93 my_pid_ = getpid();
Austin Schuhbc9a2ab2015-11-26 16:20:17 -080094 ds_ =
95#ifdef WPILIB2015
96 DriverStation::GetInstance();
97#else
98 &DriverStation::GetInstance();
99#endif
Brian Silvermanc7e8fdd2015-12-06 02:48:27 -0500100 pdp_.reset(new PowerDistributionPanel());
Comran Morshed41ed7c22015-11-04 21:03:37 +0000101
102 LOG(INFO, "Things are now started\n");
103
104 ::aos::SetCurrentThreadRealtimePriority(kPriority);
105 while (run_) {
106 ::aos::time::PhasedLoopXMS(5, 4000);
107 RunIteration();
108 }
109 }
110
111 void RunIteration() {
Brian Silvermanc7e8fdd2015-12-06 02:48:27 -0500112 ::frc971::wpilib::SendRobotState(my_pid_, ds_, pdp_.get());
Comran Morshed41ed7c22015-11-04 21:03:37 +0000113
114 // Drivetrain
115 {
116 auto drivetrain_message = drivetrain_queue.position.MakeMessage();
117 drivetrain_message->right_encoder =
118 drivetrain_translate(drivetrain_right_encoder_->GetRaw());
119 drivetrain_message->left_encoder =
120 -drivetrain_translate(drivetrain_left_encoder_->GetRaw());
Brian Silverman51091a02015-12-26 15:56:58 -0800121 drivetrain_message->left_speed =
122 drivetrain_velocity_translate(drivetrain_left_encoder_->GetPeriod());
123 drivetrain_message->right_speed =
124 drivetrain_velocity_translate(drivetrain_right_encoder_->GetPeriod());
Comran Morshed41ed7c22015-11-04 21:03:37 +0000125
126 drivetrain_message.Send();
127 }
128
129 // Rollers
130 {
131 auto rollers_message = rollers_queue.position.MakeMessage();
132 rollers_message.Send();
133 }
134 }
135
136 void Quit() { run_ = false; }
137
138 private:
139 static const int kPriority = 30;
140 static const int kInterruptPriority = 55;
141
142 int32_t my_pid_;
143 DriverStation *ds_;
Brian Silvermanc7e8fdd2015-12-06 02:48:27 -0500144 ::std::unique_ptr<PowerDistributionPanel> pdp_;
Comran Morshed41ed7c22015-11-04 21:03:37 +0000145
146 ::std::unique_ptr<Encoder> drivetrain_left_encoder_;
147 ::std::unique_ptr<Encoder> drivetrain_right_encoder_;
148
149 ::std::atomic<bool> run_{true};
150};
151
152// Writes out our pneumatic outputs.
153class SolenoidWriter {
154 public:
155 SolenoidWriter(const ::std::unique_ptr<::frc971::wpilib::BufferedPcm> &pcm)
156 : pcm_(pcm),
157 drivetrain_(".y2014_bot3.control_loops.drivetrain_queue.output"),
158 rollers_(".y2014_bot3.control_loops.rollers_queue.output") {}
159
160 void set_pressure_switch(::std::unique_ptr<DigitalInput> pressure_switch) {
161 pressure_switch_ = ::std::move(pressure_switch);
162 }
163
164 void set_compressor_relay(::std::unique_ptr<Relay> compressor_relay) {
165 compressor_relay_ = ::std::move(compressor_relay);
166 }
167
168 void set_drivetrain_left(::std::unique_ptr<BufferedSolenoid> s) {
169 drivetrain_left_ = ::std::move(s);
170 }
171
172 void set_drivetrain_right(::std::unique_ptr<BufferedSolenoid> s) {
173 drivetrain_right_ = ::std::move(s);
174 }
175
176 void set_rollers_front(::std::unique_ptr<BufferedSolenoid> s) {
177 rollers_front_ = ::std::move(s);
178 }
179
180 void set_rollers_back(::std::unique_ptr<BufferedSolenoid> s) {
181 rollers_back_ = ::std::move(s);
182 }
183
184 void operator()() {
185 ::aos::SetCurrentThreadName("Solenoids");
186 ::aos::SetCurrentThreadRealtimePriority(30);
187
188 while (run_) {
189 ::aos::time::PhasedLoopXMS(20, 1000);
190 // Drivetrain
191 {
192 drivetrain_.FetchLatest();
193 if (drivetrain_.get()) {
194 LOG_STRUCT(DEBUG, "solenoids", *drivetrain_);
195 drivetrain_left_->Set(drivetrain_->left_high);
196 drivetrain_right_->Set(drivetrain_->right_high);
197 }
198 }
199
200 // Intake
201 {
202 rollers_.FetchLatest();
203 if (rollers_.get()) {
204 LOG_STRUCT(DEBUG, "solenoids", *rollers_);
205 rollers_front_->Set(rollers_->front_extended);
206 rollers_back_->Set(rollers_->back_extended);
207 }
208 }
209
210 // Compressor
211 ::aos::joystick_state.FetchLatest();
212 {
213 ::frc971::wpilib::PneumaticsToLog to_log;
214 {
215 // Refill if pneumatic pressure goes too low.
216 const bool compressor_on = !pressure_switch_->Get();
217 to_log.compressor_on = compressor_on;
218 if (compressor_on) {
219 compressor_relay_->Set(Relay::kForward);
220 } else {
221 compressor_relay_->Set(Relay::kOff);
222 }
223 }
224
225 pcm_->Flush();
226 to_log.read_solenoids = pcm_->GetAll();
227 LOG_STRUCT(DEBUG, "pneumatics info", to_log);
228 }
229 }
230 }
231
232 void Quit() { run_ = false; }
233
234 private:
235 const ::std::unique_ptr<BufferedPcm> &pcm_;
236
237 ::std::unique_ptr<BufferedSolenoid> drivetrain_left_, drivetrain_right_;
238 ::std::unique_ptr<BufferedSolenoid> rollers_front_, rollers_back_;
239
240 ::std::unique_ptr<DigitalInput> pressure_switch_;
241 ::std::unique_ptr<Relay> compressor_relay_;
242
243 ::aos::Queue<::y2014_bot3::control_loops::DrivetrainQueue::Output>
244 drivetrain_;
245 ::aos::Queue<::y2014_bot3::control_loops::RollersQueue::Output> rollers_;
246
247 ::std::atomic<bool> run_{true};
248};
249
250// Writes out drivetrain voltages.
251class DrivetrainWriter : public LoopOutputHandler {
252 public:
253 void set_left_drivetrain_talon(::std::unique_ptr<Talon> t) {
254 left_drivetrain_talon_ = ::std::move(t);
255 }
256
257 void set_right_drivetrain_talon(::std::unique_ptr<Talon> t) {
258 right_drivetrain_talon_ = ::std::move(t);
259 }
260
261 private:
262 virtual void Read() override {
263 ::y2014_bot3::control_loops::drivetrain_queue.output.FetchAnother();
264 }
265
266 virtual void Write() override {
267 auto &queue = ::y2014_bot3::control_loops::drivetrain_queue.output;
268 LOG_STRUCT(DEBUG, "will output", *queue);
269 left_drivetrain_talon_->Set(-queue->left_voltage / 12.0);
270 right_drivetrain_talon_->Set(queue->right_voltage / 12.0);
271 }
272
273 virtual void Stop() override {
274 LOG(WARNING, "drivetrain output too old\n");
275 left_drivetrain_talon_->Disable();
276 right_drivetrain_talon_->Disable();
277 }
278
279 ::std::unique_ptr<Talon> left_drivetrain_talon_;
280 ::std::unique_ptr<Talon> right_drivetrain_talon_;
281};
282
283// Writes out rollers voltages.
284class RollersWriter : public LoopOutputHandler {
285 public:
286 void set_rollers_front_intake_talon(::std::unique_ptr<Talon> t_left, ::std::unique_ptr<Talon> t_right) {
287 rollers_front_left_intake_talon_ = ::std::move(t_left);
288 rollers_front_right_intake_talon_ = ::std::move(t_right);
289 }
290
291 void set_rollers_back_intake_talon(::std::unique_ptr<Talon> t_left, ::std::unique_ptr<Talon> t_right) {
292 rollers_back_left_intake_talon_ = ::std::move(t_left);
293 rollers_back_right_intake_talon_ = ::std::move(t_right);
294 }
295
296 void set_rollers_low_goal_talon(::std::unique_ptr<Talon> t) {
297 rollers_low_goal_talon_ = ::std::move(t);
298 }
299
300 private:
301 virtual void Read() override {
302 ::y2014_bot3::control_loops::rollers_queue.output.FetchAnother();
303 }
304
305 virtual void Write() override {
306 auto &queue = ::y2014_bot3::control_loops::rollers_queue.output;
307 LOG_STRUCT(DEBUG, "will output", *queue);
308 rollers_front_left_intake_talon_->Set(queue->front_intake_voltage / 12.0);
309 rollers_front_right_intake_talon_->Set(-(queue->front_intake_voltage / 12.0));
310 rollers_back_left_intake_talon_->Set(queue->back_intake_voltage / 12.0);
311 rollers_back_right_intake_talon_->Set(-(queue->back_intake_voltage / 12.0));
312 rollers_low_goal_talon_->Set(queue->low_goal_voltage / 12.0);
313 }
314
315 virtual void Stop() override {
316 LOG(WARNING, "Intake output too old\n");
317 rollers_front_left_intake_talon_->Disable();
318 rollers_front_right_intake_talon_->Disable();
319 rollers_back_left_intake_talon_->Disable();
320 rollers_back_right_intake_talon_->Disable();
321 rollers_low_goal_talon_->Disable();
322 }
323
324 ::std::unique_ptr<Talon> rollers_front_left_intake_talon_,
325 rollers_back_left_intake_talon_, rollers_front_right_intake_talon_,
326 rollers_back_right_intake_talon_, rollers_low_goal_talon_;
327};
328
329// TODO(brian): Replace this with ::std::make_unique once all our toolchains
330// have support.
331template <class T, class... U>
332std::unique_ptr<T> make_unique(U &&... u) {
333 return std::unique_ptr<T>(new T(std::forward<U>(u)...));
334}
335
336class WPILibRobot : public RobotBase {
337 public:
338 ::std::unique_ptr<Encoder> make_encoder(int index) {
339 return make_unique<Encoder>(10 + index * 2, 11 + index * 2, false,
340 Encoder::k4X);
341 }
342 virtual void StartCompetition() {
343 ::aos::InitNRT();
344 ::aos::SetCurrentThreadName("StartCompetition");
345
346 JoystickSender joystick_sender;
347 ::std::thread joystick_thread(::std::ref(joystick_sender));
348
349 //TODO(comran): IO ports are placeholders at the moment, so match them to
350 // the robot before turning on.
351
352 // Sensors
353 SensorReader reader;
354 LOG(INFO, "Creating the reader\n");
355 reader.set_drivetrain_left_encoder(make_encoder(4));
356 reader.set_drivetrain_right_encoder(make_encoder(5));
357
358 ::std::thread reader_thread(::std::ref(reader));
359 GyroSender gyro_sender;
360 ::std::thread gyro_thread(::std::ref(gyro_sender));
361
362 // Outputs
363 DrivetrainWriter drivetrain_writer;
364 drivetrain_writer.set_left_drivetrain_talon(
365 ::std::unique_ptr<Talon>(new Talon(2)));
366 drivetrain_writer.set_right_drivetrain_talon(
367 ::std::unique_ptr<Talon>(new Talon(5)));
368 ::std::thread drivetrain_writer_thread(::std::ref(drivetrain_writer));
369
370 RollersWriter rollers_writer;
371 rollers_writer.set_rollers_front_intake_talon(
372 ::std::unique_ptr<Talon>(new Talon(3)), ::std::unique_ptr<Talon>(new Talon(7)));
373 rollers_writer.set_rollers_back_intake_talon(
374 ::std::unique_ptr<Talon>(new Talon(1)), ::std::unique_ptr<Talon>(new Talon(6)));
375
376 rollers_writer.set_rollers_low_goal_talon(
377 ::std::unique_ptr<Talon>(new Talon(4)));
378 ::std::thread rollers_writer_thread(::std::ref(rollers_writer));
379
380 ::std::unique_ptr<::frc971::wpilib::BufferedPcm> pcm(
381 new ::frc971::wpilib::BufferedPcm());
382 SolenoidWriter solenoid_writer(pcm);
383 solenoid_writer.set_drivetrain_left(pcm->MakeSolenoid(6));
384 solenoid_writer.set_drivetrain_right(pcm->MakeSolenoid(5));
385 solenoid_writer.set_rollers_front(pcm->MakeSolenoid(2));
386 solenoid_writer.set_rollers_back(pcm->MakeSolenoid(4));
387
388 // Don't change the following IDs.
389 solenoid_writer.set_pressure_switch(make_unique<DigitalInput>(9));
390 solenoid_writer.set_compressor_relay(make_unique<Relay>(0));
391 ::std::thread solenoid_thread(::std::ref(solenoid_writer));
392
393 // Wait forever. Not much else to do...
394 PCHECK(select(0, nullptr, nullptr, nullptr, nullptr));
395
396 LOG(ERROR, "Exiting WPILibRobot\n");
397
398 joystick_sender.Quit();
399 joystick_thread.join();
400 reader.Quit();
401 reader_thread.join();
402 gyro_sender.Quit();
403 gyro_thread.join();
404
405 drivetrain_writer.Quit();
406 drivetrain_writer_thread.join();
407
408 rollers_writer.Quit();
409 rollers_writer_thread.join();
410
411 solenoid_writer.Quit();
412 solenoid_thread.join();
413
414 ::aos::Cleanup();
415 }
416};
417
418} // namespace wpilib
419} // namespace frc971
420
421START_ROBOT_CLASS(::frc971::wpilib::WPILibRobot);