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