blob: a4999258f47d56faf22d88f091d4cd6a0ea5be15 [file] [log] [blame]
brians343bc112013-02-10 01:53:46 +00001#include <stdio.h>
2#include <string.h>
3#include <unistd.h>
4#include <math.h>
5
6#include "aos/aos_core.h"
7#include "aos/atom_code/input/FRCComm.h"
8#include "aos/atom_code/input/JoystickInput.h"
9
10#include "frc971/input/AutoMode.q.h"
James Kuszmaulf254c1a2013-03-10 16:31:26 -070011#include "frc971/control_loops/drivetrain/drivetrain.q.h"
brians343bc112013-02-10 01:53:46 +000012#include "frc971/queues/GyroAngle.q.h"
13#include "frc971/queues/Piston.q.h"
Brian Silverman687f5242013-03-16 13:57:59 -070014#include "frc971/control_loops/wrist/wrist_motor.q.h"
15#include "frc971/control_loops/index/index_motor.q.h"
16#include "frc971/control_loops/shooter/shooter_motor.q.h"
17#include "frc971/control_loops/angle_adjust/angle_adjust_motor.q.h"
brians343bc112013-02-10 01:53:46 +000018
19using ::frc971::control_loops::drivetrain;
20using ::frc971::control_loops::shifters;
21using ::frc971::sensors::gyro;
Brian Silverman687f5242013-03-16 13:57:59 -070022using ::frc971::control_loops::wrist;
23using ::frc971::control_loops::index_loop;
24using ::frc971::control_loops::shooter;
25using ::frc971::control_loops::angle_adjust;
brians343bc112013-02-10 01:53:46 +000026
27namespace frc971 {
28
29class JoystickReader : public aos::JoystickInput {
30 public:
Brian Silverman8a82f382013-03-16 14:12:01 -070031 static const bool kWristAlwaysDown = false;
32
brians343bc112013-02-10 01:53:46 +000033 JoystickReader() : aos::JoystickInput() {
34 shifters.MakeWithBuilder().set(true).Send();
35 }
36
37 virtual void RunIteration() {
38 static bool is_high_gear = false;
39
40 if (Pressed(0, AUTONOMOUS)) {
41 if (PosEdge(0, ENABLED)){
42 LOG(INFO, "Starting auto mode\n");
43 AutoMode.Start();
44 }
45 if (NegEdge(0, ENABLED)) {
46 LOG(INFO, "Stopping auto mode\n");
47 AutoMode.Stop();
48 }
49 } else { // teleop
50 bool is_control_loop_driving = false;
51 double left_goal = 0.0;
52 double right_goal = 0.0;
53 const double wheel = control_data_.stick0Axis1 / 127.0;
54 const double throttle = -control_data_.stick1Axis2 / 127.0;
55 const double kThrottleGain = 1.0 / 2.5;
56 if (Pressed(0, 7) || Pressed(0, 11)) {
57 static double distance = 0.0;
58 static double angle = 0.0;
59 static double filtered_goal_distance = 0.0;
60 if (PosEdge(0, 7) || PosEdge(0, 11)) {
61 if (drivetrain.position.FetchLatest() && gyro.FetchLatest()) {
62 distance = (drivetrain.position->left_encoder +
63 drivetrain.position->right_encoder) / 2.0
64 - throttle * kThrottleGain / 2.0;
65 angle = gyro->angle;
66 filtered_goal_distance = distance;
67 }
68 }
69 is_control_loop_driving = true;
70
71 //const double gyro_angle = Gyro.View().angle;
72 const double goal_theta = angle - wheel * 0.27;
73 const double goal_distance = distance + throttle * kThrottleGain;
74 const double robot_width = 22.0 / 100.0 * 2.54;
75 const double kMaxVelocity = 0.6;
76 if (goal_distance > kMaxVelocity * 0.02 + filtered_goal_distance) {
77 filtered_goal_distance += kMaxVelocity * 0.02;
78 } else if (goal_distance < -kMaxVelocity * 0.02 + filtered_goal_distance) {
79 filtered_goal_distance -= kMaxVelocity * 0.02;
80 } else {
81 filtered_goal_distance = goal_distance;
82 }
83 left_goal = filtered_goal_distance - robot_width * goal_theta / 2.0;
84 right_goal = filtered_goal_distance + robot_width * goal_theta / 2.0;
85 is_high_gear = false;
86
87 LOG(DEBUG, "Left goal %f Right goal %f\n", left_goal, right_goal);
88 }
89 if (!(drivetrain.goal.MakeWithBuilder()
90 .steering(wheel)
91 .throttle(throttle)
92 .highgear(is_high_gear).quickturn(Pressed(0, 5))
93 .control_loop_driving(is_control_loop_driving)
94 .left_goal(left_goal).right_goal(right_goal).Send())) {
95 LOG(WARNING, "sending stick values failed\n");
96 }
97
98 if (PosEdge(1, 1)) {
99 is_high_gear = false;
100 }
101 if (PosEdge(1, 3)) {
102 is_high_gear = true;
103 }
Brian Silverman687f5242013-03-16 13:57:59 -0700104
Brian Silverman1c0cb8b2013-03-15 23:19:59 -0700105 // Where the wrist should be to pick up a frisbee.
106 static const double kWristPickup = -0.674;
107 // Where the wrist gets stored when up.
108 // All the way up is 1.5.
109 static const double kWristUp = 1.43;
110 static double wrist_down_position = kWristPickup;
111 index_loop.status.FetchLatest();
112 if (index_loop.status.get()) {
113 if (index_loop.status->hopper_disc_count >= 4) {
114 wrist_down_position = -0.4;
115 } else {
116 wrist_down_position = kWristPickup;
117 }
118 }
119 wrist.goal.MakeWithBuilder()
120 .goal(Pressed(2, 10) ? wrist_down_position : kWristUp).Send();
Brian Silverman687f5242013-03-16 13:57:59 -0700121
Brian Silverman8a82f382013-03-16 14:12:01 -0700122 ::aos::ScopedMessagePtr<control_loops::ShooterLoop::Goal> shooter_goal =
123 shooter.goal.MakeMessage();
124 shooter_goal->velocity = 0;
125 static double angle_adjust_goal = 0;
126 if (Pressed(2, 3)) {
127 // short shot
128 shooter_goal->velocity = 200;
Brian Silverman8376bd22013-03-15 21:50:11 -0700129 angle_adjust_goal = 0.42;
Brian Silverman8a82f382013-03-16 14:12:01 -0700130 } else if (Pressed(2, 5)) {
131 // medium shot
132 shooter_goal->velocity = 220;
133 angle_adjust_goal = 0.45;
134 } else if (Pressed(2, 6)) {
135 // long shot
136 shooter_goal->velocity = 240;
137 angle_adjust_goal = 0.55;
138 }
139 angle_adjust.goal.MakeWithBuilder().goal(angle_adjust_goal).Send();
Brian Silverman687f5242013-03-16 13:57:59 -0700140
Brian Silverman8a82f382013-03-16 14:12:01 -0700141 ::aos::ScopedMessagePtr<control_loops::IndexLoop::Goal> index_goal =
142 index_loop.goal.MakeMessage();
143 // TODO(brians): replace these with the enum values
144 if (Pressed(2, 11)) {
145 // FIRE
146 index_goal->goal_state = 4;
147 } else if (shooter_goal->velocity != 0) {
148 // get ready to shoot
149 index_goal->goal_state = 3;
150 } else if (Pressed(2, 9)) {
151 // intake
152 index_goal->goal_state = 2;
153 } else {
154 // get ready to intake
155 index_goal->goal_state = 1;
156 }
Brian Silverman687f5242013-03-16 13:57:59 -0700157
Brian Silverman8a82f382013-03-16 14:12:01 -0700158 index_goal.Send();
159 shooter_goal.Send();
brians343bc112013-02-10 01:53:46 +0000160 }
161 }
162};
163
164} // namespace frc971
165
166AOS_RUN(frc971::JoystickReader)