blob: fd265c40946bafaeda064c61d1818e0fab4f0f12 [file] [log] [blame]
milind-u37385182023-02-20 15:07:28 -08001#include "y2023/control_loops/superstructure/arm/arm.h"
2
milind-u18a901d2023-02-17 21:51:55 -08003#include "y2023/control_loops/superstructure/roll/integral_hybrid_roll_plant.h"
4#include "y2023/control_loops/superstructure/roll/integral_roll_plant.h"
5
milind-u37385182023-02-20 15:07:28 -08006namespace y2023 {
7namespace control_loops {
8namespace superstructure {
9namespace arm {
10namespace {
11
12namespace chrono = ::std::chrono;
13using ::aos::monotonic_clock;
14
15constexpr int kMaxBrownoutCount = 4;
16
17} // namespace
18
19Arm::Arm(std::shared_ptr<const constants::Values> values)
20 : values_(values),
21 state_(ArmState::UNINITIALIZED),
22 proximal_zeroing_estimator_(values_->arm_proximal.zeroing),
23 distal_zeroing_estimator_(values_->arm_distal.zeroing),
milind-u18a901d2023-02-17 21:51:55 -080024 roll_joint_zeroing_estimator_(values_->roll_joint.zeroing),
milind-u37385182023-02-20 15:07:28 -080025 proximal_offset_(0.0),
26 distal_offset_(0.0),
milind-u18a901d2023-02-17 21:51:55 -080027 roll_joint_offset_(0.0),
28 alpha_unitizer_((::Eigen::DiagonalMatrix<double, 3>().diagonal()
29 << (1.0 / kAlpha0Max()),
30 (1.0 / kAlpha1Max()), (1.0 / kAlpha2Max()))
milind-u37385182023-02-20 15:07:28 -080031 .finished()),
32 dynamics_(kArmConstants),
milind-u37385182023-02-20 15:07:28 -080033 close_enough_for_full_power_(false),
34 brownout_count_(0),
milind-u18a901d2023-02-17 21:51:55 -080035 roll_joint_loop_(roll::MakeIntegralRollLoop()),
36 hybrid_roll_joint_loop_(roll::MakeIntegralHybridRollLoop()),
milind-u37385182023-02-20 15:07:28 -080037 arm_ekf_(&dynamics_),
milind-u18a901d2023-02-17 21:51:55 -080038 search_graph_(MakeSearchGraph(&dynamics_, &trajectories_, alpha_unitizer_,
39 kVMax(), &hybrid_roll_joint_loop_)),
milind-u37385182023-02-20 15:07:28 -080040 // Go to the start of the first trajectory.
milind-u18a901d2023-02-17 21:51:55 -080041 follower_(&dynamics_, &hybrid_roll_joint_loop_, NeutralPosPoint()),
milind-u37385182023-02-20 15:07:28 -080042 points_(PointList()),
43 current_node_(0) {
44 int i = 0;
45 for (const auto &trajectory : trajectories_) {
46 AOS_LOG(INFO, "trajectory length for edge node %d: %f\n", i,
47 trajectory.trajectory.path().length());
48 ++i;
49 }
50}
51
52void Arm::Reset() { state_ = ArmState::UNINITIALIZED; }
53
milind-u3b91b752023-02-25 15:21:06 -080054namespace {
55
56// Proximal joint center in xy space
57constexpr std::pair<double, double> kJointCenter = {-0.203, 0.787};
58
59std::tuple<double, double, int> ArmThetasToXY(double theta_proximal,
60 double theta_distal) {
61 double theta_proximal_shifted = M_PI / 2.0 - theta_proximal;
62 double theta_distal_shifted = M_PI / 2.0 - theta_distal;
63
64 double x = std::cos(theta_proximal_shifted) * kArmConstants.l0 +
65 std::cos(theta_distal_shifted) * kArmConstants.l1 +
66 kJointCenter.first;
67 double y = std::sin(theta_proximal_shifted) * kArmConstants.l0 +
68 std::sin(theta_distal_shifted) * kArmConstants.l1 +
69 kJointCenter.second;
70
71 int circular_index =
72 std::floor((theta_distal_shifted - theta_proximal_shifted) / M_PI);
73
74 return std::make_tuple(x, y, circular_index);
75}
76
77} // namespace
78
milind-u37385182023-02-20 15:07:28 -080079flatbuffers::Offset<superstructure::ArmStatus> Arm::Iterate(
80 const ::aos::monotonic_clock::time_point /*monotonic_now*/,
81 const uint32_t *unsafe_goal, const superstructure::ArmPosition *position,
82 bool trajectory_override, double *proximal_output, double *distal_output,
Maxwell Henderson5938a832023-02-23 09:33:15 -080083 double *roll_joint_output, flatbuffers::FlatBufferBuilder *fbb) {
84 ::Eigen::Matrix<double, 2, 1> Y;
milind-u37385182023-02-20 15:07:28 -080085 const bool outputs_disabled =
milind-u18a901d2023-02-17 21:51:55 -080086 ((proximal_output == nullptr) || (distal_output == nullptr) ||
87 (roll_joint_output == nullptr));
milind-u37385182023-02-20 15:07:28 -080088 if (outputs_disabled) {
89 ++brownout_count_;
90 } else {
91 brownout_count_ = 0;
92 }
93
milind-u18a901d2023-02-17 21:51:55 -080094 // TODO(milind): should we default to the closest position?
95 uint32_t filtered_goal = arm::NeutralPosIndex();
milind-u37385182023-02-20 15:07:28 -080096 if (unsafe_goal != nullptr) {
97 filtered_goal = *unsafe_goal;
98 }
99
milind-u18a901d2023-02-17 21:51:55 -0800100 ::Eigen::Matrix<double, 2, 1> Y_arm;
101 Y_arm << position->proximal()->encoder() + proximal_offset_,
milind-u37385182023-02-20 15:07:28 -0800102 position->distal()->encoder() + distal_offset_;
milind-u18a901d2023-02-17 21:51:55 -0800103 ::Eigen::Matrix<double, 1, 1> Y_roll_joint;
104 Y_roll_joint << position->roll_joint()->encoder() + roll_joint_offset_;
milind-u37385182023-02-20 15:07:28 -0800105
106 proximal_zeroing_estimator_.UpdateEstimate(*position->proximal());
107 distal_zeroing_estimator_.UpdateEstimate(*position->distal());
milind-u18a901d2023-02-17 21:51:55 -0800108 roll_joint_zeroing_estimator_.UpdateEstimate(*position->roll_joint());
milind-u37385182023-02-20 15:07:28 -0800109
110 if (proximal_output != nullptr) {
111 *proximal_output = 0.0;
112 }
113 if (distal_output != nullptr) {
114 *distal_output = 0.0;
115 }
milind-u18a901d2023-02-17 21:51:55 -0800116 if (roll_joint_output != nullptr) {
117 *roll_joint_output = 0.0;
118 }
milind-u37385182023-02-20 15:07:28 -0800119
milind-u18a901d2023-02-17 21:51:55 -0800120 arm_ekf_.Correct(Y_arm, kDt());
121 roll_joint_loop_.Correct(Y_roll_joint);
milind-u37385182023-02-20 15:07:28 -0800122
123 if (::std::abs(arm_ekf_.X_hat(0) - follower_.theta(0)) <= 0.05 &&
milind-u18a901d2023-02-17 21:51:55 -0800124 ::std::abs(arm_ekf_.X_hat(2) - follower_.theta(1)) <= 0.05 &&
125 ::std::abs(roll_joint_loop_.X_hat(0) - follower_.theta(2)) <= 0.05) {
milind-u37385182023-02-20 15:07:28 -0800126 close_enough_for_full_power_ = true;
127 }
128 if (::std::abs(arm_ekf_.X_hat(0) - follower_.theta(0)) >= 1.10 ||
milind-u18a901d2023-02-17 21:51:55 -0800129 ::std::abs(arm_ekf_.X_hat(2) - follower_.theta(1)) >= 1.10 ||
130 ::std::abs(roll_joint_loop_.X_hat(0) - follower_.theta(2)) >= 0.50) {
milind-u37385182023-02-20 15:07:28 -0800131 close_enough_for_full_power_ = false;
132 }
133
134 switch (state_) {
135 case ArmState::UNINITIALIZED:
136 // Wait in the uninitialized state until the intake is initialized.
137 AOS_LOG(DEBUG, "Uninitialized, waiting for intake\n");
138 state_ = ArmState::ZEROING;
139 proximal_zeroing_estimator_.Reset();
140 distal_zeroing_estimator_.Reset();
milind-u18a901d2023-02-17 21:51:55 -0800141 roll_joint_zeroing_estimator_.Reset();
milind-u37385182023-02-20 15:07:28 -0800142 break;
143
144 case ArmState::ZEROING:
145 // Zero by not moving.
milind-u18a901d2023-02-17 21:51:55 -0800146 if (zeroed()) {
milind-u37385182023-02-20 15:07:28 -0800147 state_ = ArmState::DISABLED;
148
149 proximal_offset_ = proximal_zeroing_estimator_.offset();
150 distal_offset_ = distal_zeroing_estimator_.offset();
milind-u18a901d2023-02-17 21:51:55 -0800151 roll_joint_offset_ = roll_joint_zeroing_estimator_.offset();
milind-u37385182023-02-20 15:07:28 -0800152
milind-u18a901d2023-02-17 21:51:55 -0800153 Y_arm << position->proximal()->encoder() + proximal_offset_,
milind-u37385182023-02-20 15:07:28 -0800154 position->distal()->encoder() + distal_offset_;
milind-u18a901d2023-02-17 21:51:55 -0800155 Y_roll_joint << position->roll_joint()->encoder() + roll_joint_offset_;
milind-u37385182023-02-20 15:07:28 -0800156
157 // TODO(austin): Offset ekf rather than reset it. Since we aren't
158 // moving at this point, it's pretty safe to do this.
milind-u18a901d2023-02-17 21:51:55 -0800159 ::Eigen::Matrix<double, 4, 1> X_arm;
160 X_arm << Y_arm(0), 0.0, Y_arm(1), 0.0;
161 arm_ekf_.Reset(X_arm);
162
163 ::Eigen::Matrix<double, 3, 1> X_roll_joint;
164 X_roll_joint << Y_roll_joint(0), 0.0, 0.0;
165 roll_joint_loop_.mutable_X_hat() = X_roll_joint;
milind-u37385182023-02-20 15:07:28 -0800166 } else {
167 break;
168 }
169 [[fallthrough]];
170
171 case ArmState::DISABLED: {
172 follower_.SwitchTrajectory(nullptr);
173 close_enough_for_full_power_ = false;
174
milind-u18a901d2023-02-17 21:51:55 -0800175 const ::Eigen::Matrix<double, 3, 1> current_theta =
176 (::Eigen::Matrix<double, 3, 1>() << arm_ekf_.X_hat(0),
177 arm_ekf_.X_hat(2), roll_joint_loop_.X_hat(0))
milind-u37385182023-02-20 15:07:28 -0800178 .finished();
179 uint32_t best_index = 0;
180 double best_distance = (points_[0] - current_theta).norm();
181 uint32_t current_index = 0;
milind-u18a901d2023-02-17 21:51:55 -0800182 for (const ::Eigen::Matrix<double, 3, 1> &point : points_) {
milind-u37385182023-02-20 15:07:28 -0800183 const double new_distance = (point - current_theta).norm();
184 if (new_distance < best_distance) {
185 best_distance = new_distance;
186 best_index = current_index;
187 }
188 ++current_index;
189 }
190 follower_.set_theta(points_[best_index]);
191 current_node_ = best_index;
192
193 if (!outputs_disabled) {
194 state_ = ArmState::GOTO_PATH;
195 } else {
196 break;
197 }
198 }
199 [[fallthrough]];
200
201 case ArmState::GOTO_PATH:
202 if (outputs_disabled) {
203 state_ = ArmState::DISABLED;
204 } else if (trajectory_override) {
205 follower_.SwitchTrajectory(nullptr);
206 current_node_ = filtered_goal;
207 follower_.set_theta(points_[current_node_]);
208 state_ = ArmState::GOTO_PATH;
209 } else if (close_enough_for_full_power_) {
210 state_ = ArmState::RUNNING;
211 }
212 break;
213
214 case ArmState::RUNNING:
215 // ESTOP if we hit the hard limits.
216 // TODO(austin): Pick some sane limits.
217 if (proximal_zeroing_estimator_.error() ||
milind-u18a901d2023-02-17 21:51:55 -0800218 distal_zeroing_estimator_.error() ||
219 roll_joint_zeroing_estimator_.error()) {
milind-u37385182023-02-20 15:07:28 -0800220 AOS_LOG(ERROR, "Zeroing error ESTOP\n");
221 state_ = ArmState::ESTOP;
222 } else if (outputs_disabled && brownout_count_ > kMaxBrownoutCount) {
223 state_ = ArmState::DISABLED;
224 } else if (trajectory_override) {
225 follower_.SwitchTrajectory(nullptr);
226 current_node_ = filtered_goal;
227 follower_.set_theta(points_[current_node_]);
228 state_ = ArmState::GOTO_PATH;
229 }
230 break;
231
232 case ArmState::ESTOP:
233 AOS_LOG(ERROR, "Estop\n");
234 break;
235 }
236
237 const bool disable = outputs_disabled || (state_ != ArmState::RUNNING &&
238 state_ != ArmState::GOTO_PATH);
239 if (disable) {
240 close_enough_for_full_power_ = false;
241 }
242
243 if (state_ == ArmState::RUNNING && unsafe_goal != nullptr) {
244 if (current_node_ != filtered_goal) {
245 AOS_LOG(INFO, "Goal is different\n");
246 if (filtered_goal >= search_graph_.num_vertexes()) {
247 AOS_LOG(ERROR, "goal node out of range ESTOP\n");
248 state_ = ArmState::ESTOP;
249 } else if (follower_.path_distance_to_go() > 1e-3) {
250 // Still on the old path segment. Can't change yet.
251 } else {
252 search_graph_.SetGoal(filtered_goal);
253
254 size_t min_edge = 0;
255 double min_cost = ::std::numeric_limits<double>::infinity();
256 for (const SearchGraph::HalfEdge &edge :
257 search_graph_.Neighbors(current_node_)) {
258 const double cost = search_graph_.GetCostToGoal(edge.dest);
259 if (cost < min_cost) {
260 min_edge = edge.edge_id;
261 min_cost = cost;
262 }
263 }
264 // Ok, now we know which edge we are on. Figure out the path and
265 // trajectory.
266 const SearchGraph::Edge &next_edge = search_graph_.edges()[min_edge];
267 AOS_LOG(INFO, "Switching from node %d to %d along edge %d\n",
268 static_cast<int>(current_node_),
269 static_cast<int>(next_edge.end), static_cast<int>(min_edge));
270 vmax_ = trajectories_[min_edge].vmax;
271 follower_.SwitchTrajectory(&trajectories_[min_edge].trajectory);
272 current_node_ = next_edge.end;
273 }
274 }
275 }
276
277 const double max_operating_voltage =
278 close_enough_for_full_power_
279 ? kOperatingVoltage()
280 : (state_ == ArmState::GOTO_PATH ? kGotoPathVMax() : kPathlessVMax());
milind-u18a901d2023-02-17 21:51:55 -0800281 ::Eigen::Matrix<double, 9, 1> X_hat;
282 X_hat.block<6, 1>(0, 0) = arm_ekf_.X_hat();
283 X_hat.block<3, 1>(6, 0) = roll_joint_loop_.X_hat();
284
285 follower_.Update(X_hat, disable, kDt(), vmax_, max_operating_voltage);
milind-u37385182023-02-20 15:07:28 -0800286 AOS_LOG(INFO, "Max voltage: %f\n", max_operating_voltage);
287
milind-u18a901d2023-02-17 21:51:55 -0800288 arm_ekf_.Predict(follower_.U().head<2>(), kDt());
289 roll_joint_loop_.UpdateObserver(follower_.U().tail<1>(), kDtDuration());
290
milind-u37385182023-02-20 15:07:28 -0800291 flatbuffers::Offset<frc971::PotAndAbsoluteEncoderEstimatorState>
292 proximal_estimator_state_offset =
293 proximal_zeroing_estimator_.GetEstimatorState(fbb);
294 flatbuffers::Offset<frc971::PotAndAbsoluteEncoderEstimatorState>
295 distal_estimator_state_offset =
296 distal_zeroing_estimator_.GetEstimatorState(fbb);
milind-u18a901d2023-02-17 21:51:55 -0800297 flatbuffers::Offset<frc971::PotAndAbsoluteEncoderEstimatorState>
298 roll_joint_estimator_state_offset =
299 roll_joint_zeroing_estimator_.GetEstimatorState(fbb);
milind-u37385182023-02-20 15:07:28 -0800300
milind-u3b91b752023-02-25 15:21:06 -0800301 const auto [arm_x, arm_y, arm_circular_index] =
302 ArmThetasToXY(arm_ekf_.X_hat(0), arm_ekf_.X_hat(2));
303
milind-u37385182023-02-20 15:07:28 -0800304 superstructure::ArmStatus::Builder status_builder(*fbb);
305 status_builder.add_proximal_estimator_state(proximal_estimator_state_offset);
306 status_builder.add_distal_estimator_state(distal_estimator_state_offset);
milind-u18a901d2023-02-17 21:51:55 -0800307 status_builder.add_roll_joint_estimator_state(
308 roll_joint_estimator_state_offset);
milind-u37385182023-02-20 15:07:28 -0800309
310 status_builder.add_goal_theta0(follower_.theta(0));
311 status_builder.add_goal_theta1(follower_.theta(1));
milind-u18a901d2023-02-17 21:51:55 -0800312 status_builder.add_goal_theta2(follower_.theta(2));
milind-u37385182023-02-20 15:07:28 -0800313 status_builder.add_goal_omega0(follower_.omega(0));
314 status_builder.add_goal_omega1(follower_.omega(1));
milind-u18a901d2023-02-17 21:51:55 -0800315 status_builder.add_goal_omega2(follower_.omega(2));
milind-u37385182023-02-20 15:07:28 -0800316
317 status_builder.add_theta0(arm_ekf_.X_hat(0));
318 status_builder.add_theta1(arm_ekf_.X_hat(2));
milind-u18a901d2023-02-17 21:51:55 -0800319 status_builder.add_theta2(roll_joint_loop_.X_hat(0));
milind-u37385182023-02-20 15:07:28 -0800320 status_builder.add_omega0(arm_ekf_.X_hat(1));
321 status_builder.add_omega1(arm_ekf_.X_hat(3));
milind-u18a901d2023-02-17 21:51:55 -0800322 status_builder.add_omega2(roll_joint_loop_.X_hat(1));
milind-u37385182023-02-20 15:07:28 -0800323 status_builder.add_voltage_error0(arm_ekf_.X_hat(4));
324 status_builder.add_voltage_error1(arm_ekf_.X_hat(5));
milind-u18a901d2023-02-17 21:51:55 -0800325 status_builder.add_voltage_error2(roll_joint_loop_.X_hat(2));
milind-u37385182023-02-20 15:07:28 -0800326
milind-u3b91b752023-02-25 15:21:06 -0800327 status_builder.add_arm_x(arm_x);
328 status_builder.add_arm_y(arm_y);
329 status_builder.add_arm_circular_index(arm_circular_index);
330
milind-u37385182023-02-20 15:07:28 -0800331 if (!disable) {
332 *proximal_output = ::std::max(
333 -kOperatingVoltage(), ::std::min(kOperatingVoltage(), follower_.U(0)));
334 *distal_output = ::std::max(
335 -kOperatingVoltage(), ::std::min(kOperatingVoltage(), follower_.U(1)));
milind-u18a901d2023-02-17 21:51:55 -0800336 *roll_joint_output = ::std::max(
337 -kOperatingVoltage(), ::std::min(kOperatingVoltage(), follower_.U(2)));
milind-u37385182023-02-20 15:07:28 -0800338 }
339
340 status_builder.add_path_distance_to_go(follower_.path_distance_to_go());
341 status_builder.add_current_node(current_node_);
342
343 status_builder.add_zeroed(zeroed());
344 status_builder.add_estopped(estopped());
345 status_builder.add_state(state_);
346 status_builder.add_failed_solutions(follower_.failed_solutions());
347
milind-u37385182023-02-20 15:07:28 -0800348 return status_builder.Finish();
349}
350
351} // namespace arm
352} // namespace superstructure
353} // namespace control_loops
354} // namespace y2023