Apollo 10.0
自动驾驶开放平台
mpc_controller.cc
浏览该文件的文档.
1/******************************************************************************
2 * Copyright 2017 The Apollo Authors. All Rights Reserved.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *****************************************************************************/
16
18
19#include <algorithm>
20#include <iomanip>
21#include <limits>
22#include <utility>
23#include <vector>
24
25#include "Eigen/LU"
26#include "absl/strings/str_cat.h"
27
28#include "cyber/common/log.h"
29#include "cyber/time/clock.h"
35
36namespace apollo {
37namespace control {
43using Matrix = Eigen::MatrixXd;
45
46constexpr double GRA_ACC = 9.8;
47
48namespace {
49
50std::string GetLogFileName() {
51 time_t raw_time;
52 char name_buffer[80];
53 std::time(&raw_time);
54
55 std::tm time_tm;
56 localtime_r(&raw_time, &time_tm);
57 strftime(name_buffer, sizeof(name_buffer),
58 "/tmp/mpc_controller_%F_%H%M%S.csv", &time_tm);
59 return std::string(name_buffer);
60}
61
62void WriteHeaders(std::ofstream &file_stream) {}
63} // namespace
64
65MPCController::MPCController() : name_("MPC Controller") {
66 if (FLAGS_enable_csv_debug) {
67 mpc_log_file_.open(GetLogFileName());
68 mpc_log_file_ << std::fixed;
69 mpc_log_file_ << std::setprecision(6);
70 WriteHeaders(mpc_log_file_);
71 }
72 AINFO << "Using " << name_;
73}
74
76
78 vehicle_param_ = VehicleConfigHelper::Instance()->GetConfig().vehicle_param();
79
80 ts_ = control_conf_.ts();
81 if (ts_ <= 0.0) {
82 AERROR << "[MPCController] Invalid control update interval.";
83 return false;
84 }
85 cf_ = control_conf_.cf();
86 cr_ = control_conf_.cr();
90 vehicle_param_.max_steer_angle() * 180 / M_PI;
91 max_lat_acc_ = control_conf_.max_lateral_acceleration();
92
93 // TODO(Shu, Qi, Yu): add sanity check for conf values
94 // steering ratio should be positive
95 static constexpr double kEpsilon = 1e-6;
96 if (std::isnan(steer_ratio_) || steer_ratio_ < kEpsilon) {
97 AERROR << "[MPCController] steer_ratio = 0";
98 return false;
99 }
104
105 const double mass_fl = control_conf_.mass_fl();
106 const double mass_fr = control_conf_.mass_fr();
107 const double mass_rl = control_conf_.mass_rl();
108 const double mass_rr = control_conf_.mass_rr();
109 const double mass_front = mass_fl + mass_fr;
110 const double mass_rear = mass_rl + mass_rr;
111 mass_ = mass_front + mass_rear;
112
113 lf_ = wheelbase_ * (1.0 - mass_front / mass_);
114 lr_ = wheelbase_ * (1.0 - mass_rear / mass_);
115 iz_ = lf_ * lf_ * mass_front + lr_ * lr_ * mass_rear;
116
117 mpc_eps_ = control_conf_.eps();
118 mpc_max_iteration_ = control_conf_.max_iteration();
120 control_conf_.throttle_minimum_action());
122 control_conf_.brake_minimum_action());
123
124 minimum_speed_protection_ = FLAGS_minimum_speed_protection;
125 max_acceleration_when_stopped_ = FLAGS_max_acceleration_when_stopped;
127 standstill_acceleration_ = control_conf_.standstill_acceleration();
128
130 control_conf_.enable_mpc_feedforward_compensation();
131
133 control_conf_.unconstrained_control_diff_limit();
134
136 control_conf_.enable_look_ahead_back_control();
137 low_speed_bound_ = control_conf_.switch_speed();
138 low_speed_window_ = control_conf_.switch_speed_window();
139 preview_window_ = control_conf_.preview_window();
140 lookahead_station_low_speed_ = control_conf_.lookahead_station();
141 lookback_station_low_speed_ = control_conf_.lookback_station();
142 lookahead_station_high_speed_ = control_conf_.lookahead_station_high_speed();
143 lookback_station_high_speed_ = control_conf_.lookback_station_high_speed();
145 control_conf_.use_lqr_curvature_feedforward();
146
147 enable_leadlag_ = control_conf_.enable_reverse_leadlag_compensation();
148 if (enable_leadlag_) {
149 leadlag_controller_.Init(control_conf_.reverse_leadlag_conf(), ts_);
150 }
151
152 preview_time_ = control_conf_.preview_window() * ts_;
153
154 use_preview_ = control_conf_.use_preview();
155
156 use_lookup_acc_pid_ = control_conf_.use_lookup_acc_pid();
157
158 use_pitch_angle_filter_ = control_conf_.use_pitch_angle_filter();
159
160 AINFO << "[MPCController] use_preview is " << use_preview_;
162 ADEBUG << "MPC conf loaded";
163 return true;
164}
165
167 const canbus::Chassis *chassis) {
168 // TODO(QiL): Add debug information
169}
170
172 AINFO << name_ << " begin.";
173 AINFO << "[MPCController parameters]"
174 << " mass_: " << mass_ << ","
175 << " iz_: " << iz_ << ","
176 << " lf_: " << lf_ << ","
177 << " lr_: " << lr_;
178}
179
181 // Low pass filter
182 std::vector<double> den(3, 0.0);
183 std::vector<double> num(3, 0.0);
184 common::LpfCoefficients(ts_, control_conf_.cutoff_freq(), &den, &num);
187 control_conf_.pitch_angle_filter_conf().cutoff_freq(),
188 &den, &num);
191 static_cast<std::uint_fast8_t>(control_conf_.mean_filter_window_size()));
193 static_cast<std::uint_fast8_t>(control_conf_.mean_filter_window_size()));
194}
195
196Status MPCController::Init(std::shared_ptr<DependencyInjector> injector) {
197 if (!ControlTask::LoadConfig<MPCControllerConf>(&control_conf_)) {
198 AERROR << "failed to load control conf";
199 return Status(ErrorCode::CONTROL_INIT_ERROR,
200 "failed to load mpc control_conf");
201 }
202
204 AERROR << "failed to load calibration table";
205 return Status(ErrorCode::CONTROL_INIT_ERROR,
206 "mpc failed to load calibration table");
207 }
208
209 if (!LoadControlConf()) {
210 AERROR << "failed to load control conf";
211 return Status(ErrorCode::CONTROL_COMPUTE_ERROR,
212 "failed to load control_conf");
213 }
214
215 injector_ = injector;
216 // Matrix init operations.
219 matrix_a_(0, 1) = 1.0;
220 matrix_a_(1, 2) = (cf_ + cr_) / mass_;
221 matrix_a_(2, 3) = 1.0;
222 matrix_a_(3, 2) = (lf_ * cf_ - lr_ * cr_) / iz_;
223 matrix_a_(4, 5) = 1.0;
224 matrix_a_(5, 5) = 0.0;
225 // TODO(QiL): expand the model to accommodate more combined states.
226
228 matrix_a_coeff_(1, 1) = -(cf_ + cr_) / mass_;
229 matrix_a_coeff_(1, 3) = (lr_ * cr_ - lf_ * cf_) / mass_;
230 matrix_a_coeff_(2, 3) = 1.0;
231 matrix_a_coeff_(3, 1) = (lr_ * cr_ - lf_ * cf_) / iz_;
232 matrix_a_coeff_(3, 3) = -1.0 * (lf_ * lf_ * cf_ + lr_ * lr_ * cr_) / iz_;
233
234 matrix_b_ = Matrix::Zero(basic_state_size_, controls_);
235 matrix_bd_ = Matrix::Zero(basic_state_size_, controls_);
236 matrix_b_(1, 0) = cf_ / mass_;
237 matrix_b_(3, 0) = lf_ * cf_ / iz_;
238 matrix_b_(4, 1) = 0.0;
239 matrix_b_(5, 1) = -1.0;
241
242 matrix_c_ = Matrix::Zero(basic_state_size_, 1);
243 matrix_cd_ = Matrix::Zero(basic_state_size_, 1);
244
245 matrix_state_ = Matrix::Zero(basic_state_size_, 1);
246 matrix_k_ = Matrix::Zero(1, basic_state_size_);
247
248 matrix_r_ = Matrix::Identity(controls_, controls_);
249
251
252 int r_param_size = control_conf_.matrix_r_size();
253 for (int i = 0; i < r_param_size; ++i) {
254 matrix_r_(i, i) = control_conf_.matrix_r(i);
255 }
256
257 int q_param_size = control_conf_.matrix_q_size();
258 if (basic_state_size_ != q_param_size) {
259 const auto error_msg =
260 absl::StrCat("MPC controller error: matrix_q size: ", q_param_size,
261 " in parameter file not equal to basic_state_size_: ",
263 AERROR << error_msg;
264 return Status(ErrorCode::CONTROL_COMPUTE_ERROR, error_msg);
265 }
266 for (int i = 0; i < q_param_size; ++i) {
267 matrix_q_(i, i) = control_conf_.matrix_q(i);
268 }
269
270 // Update matrix_q_updated_ and matrix_r_updated_
273
275
279 ADEBUG << "[MPCController] init done!";
280 return Status::OK();
281}
282
284 if (FLAGS_enable_csv_debug && mpc_log_file_.is_open()) {
285 mpc_log_file_.close();
286 }
287}
288
289double MPCController::Wheel2SteerPct(const double wheel_angle) {
290 return wheel_angle / wheel_single_direction_max_degree_ * 100;
291}
292
294
295std::string MPCController::Name() const { return name_; }
296
298 const auto &lat_err_gain_scheduler = control_conf_.lat_err_gain_scheduler();
299 const auto &heading_err_gain_scheduler =
300 control_conf_.heading_err_gain_scheduler();
301 const auto &feedforwardterm_gain_scheduler =
302 control_conf_.feedforwardterm_gain_scheduler();
303 const auto &steer_weight_gain_scheduler =
304 control_conf_.steer_weight_gain_scheduler();
305 ADEBUG << "MPC control gain scheduler loaded";
306 Interpolation1D::DataType xy1, xy2, xy3, xy4;
307 for (const auto &scheduler : lat_err_gain_scheduler.scheduler()) {
308 xy1.push_back(std::make_pair(scheduler.speed(), scheduler.ratio()));
309 }
310 for (const auto &scheduler : heading_err_gain_scheduler.scheduler()) {
311 xy2.push_back(std::make_pair(scheduler.speed(), scheduler.ratio()));
312 }
313 for (const auto &scheduler : feedforwardterm_gain_scheduler.scheduler()) {
314 xy3.push_back(std::make_pair(scheduler.speed(), scheduler.ratio()));
315 }
316 for (const auto &scheduler : steer_weight_gain_scheduler.scheduler()) {
317 xy4.push_back(std::make_pair(scheduler.speed(), scheduler.ratio()));
318 }
319
322 << "Fail to load lateral error gain scheduler for MPC controller";
323
326 << "Fail to load heading error gain scheduler for MPC controller";
327
330 << "Fail to load feed forward term gain scheduler for MPC controller";
331
334 << "Fail to load steer weight gain scheduler for MPC controller";
335}
336
338 const localization::LocalizationEstimate *localization,
339 const canbus::Chassis *chassis,
340 const planning::ADCTrajectory *planning_published_trajectory,
341 ControlCommand *cmd) {
343 std::move(TrajectoryAnalyzer(planning_published_trajectory));
344 auto vehicle_state = injector_->vehicle_state();
345
346 // Transform the coordinate of the planning trajectory from the center of the
347 // rear-axis to the center of mass, if conditions matched
348 if (((control_conf_.trajectory_transform_to_com_reverse() &&
349 vehicle_state->gear() == canbus::Chassis::GEAR_REVERSE) ||
350 (control_conf_.trajectory_transform_to_com_reverse() &&
351 vehicle_state->gear() == canbus::Chassis::GEAR_DRIVE))) {
353 }
354
355 // Re-build the vehicle dynamic models at reverse driving (in particular,
356 // replace the lateral translational motion dynamics with the corresponding
357 // kinematic models)
358 if (vehicle_state->gear() == canbus::Chassis::GEAR_REVERSE) {
359 /*
360 A matrix (Gear Reverse)
361 [0.0, 0.0, 1.0 * v 0.0;
362 0.0, (-(c_f + c_r) / m) / v, (c_f + c_r) / m,
363 (l_r * c_r - l_f * c_f) / m / v;
364 0.0, 0.0, 0.0, 1.0;
365 0.0, ((lr * cr - lf * cf) / i_z) / v, (l_f * c_f - l_r * c_r) / i_z,
366 (-1.0 * (l_f^2 * c_f + l_r^2 * c_r) / i_z) / v;]
367 */
368 cf_ = -control_conf_.cf();
369 cr_ = -control_conf_.cr();
370 matrix_a_(0, 1) = 0.0;
371 matrix_a_coeff_(0, 2) = 1.0;
372 } else {
373 /*
374 A matrix (Gear Drive)
375 [0.0, 1.0, 0.0, 0.0;
376 0.0, (-(c_f + c_r) / m) / v, (c_f + c_r) / m,
377 (l_r * c_r - l_f * c_f) / m / v;
378 0.0, 0.0, 0.0, 1.0;
379 0.0, ((lr * cr - lf * cf) / i_z) / v, (l_f * c_f - l_r * c_r) / i_z,
380 (-1.0 * (l_f^2 * c_f + l_r^2 * c_r) / i_z) / v;]
381 */
382 cf_ = control_conf_.cf();
383 cr_ = control_conf_.cr();
384 matrix_a_(0, 1) = 1.0;
385 matrix_a_coeff_(0, 2) = 0.0;
386 }
387
388 SimpleMPCDebug *debug = cmd->mutable_debug()->mutable_simple_mpc_debug();
389 debug->Clear();
390
391 if (!use_preview_) {
393 } else {
395 }
396
397 // Update state
398 UpdateState(debug);
399
400 UpdateMatrix(debug);
401
402 FeedforwardUpdate(debug);
403
404 // Add gain scheduler for higher speed steering
405 if (FLAGS_enable_gain_scheduler) {
406 matrix_q_updated_(0, 0) =
407 matrix_q_(0, 0) *
408 lat_err_interpolation_->Interpolate(vehicle_state->linear_velocity());
409 matrix_q_updated_(2, 2) =
410 matrix_q_(2, 2) * heading_err_interpolation_->Interpolate(
411 vehicle_state->linear_velocity());
415 vehicle_state->linear_velocity());
416 matrix_r_updated_(0, 0) =
417 matrix_r_(0, 0) * steer_weight_interpolation_->Interpolate(
418 vehicle_state->linear_velocity());
419 } else {
423 }
424
425 debug->add_matrix_q_updated(matrix_q_updated_(0, 0));
426 debug->add_matrix_q_updated(matrix_q_updated_(1, 1));
427 debug->add_matrix_q_updated(matrix_q_updated_(2, 2));
428 debug->add_matrix_q_updated(matrix_q_updated_(3, 3));
429
430 debug->add_matrix_r_updated(matrix_r_updated_(0, 0));
431 debug->add_matrix_r_updated(matrix_r_updated_(1, 1));
432
433 Matrix control_matrix = Matrix::Zero(controls_, 1);
434 std::vector<Matrix> control(horizon_, control_matrix);
435
436 Matrix control_gain_matrix = Matrix::Zero(controls_, basic_state_size_);
437 std::vector<Matrix> control_gain(horizon_, control_gain_matrix);
438
439 Matrix addition_gain_matrix = Matrix::Zero(controls_, 1);
440 std::vector<Matrix> addition_gain(horizon_, addition_gain_matrix);
441
442 Matrix reference_state = Matrix::Zero(basic_state_size_, 1);
443 std::vector<Matrix> reference(horizon_, reference_state);
444
445 Matrix lower_bound(controls_, 1);
447
448 Matrix upper_bound(controls_, 1);
450
451 const double max = std::numeric_limits<double>::max();
452 Matrix lower_state_bound(basic_state_size_, 1);
453 Matrix upper_state_bound(basic_state_size_, 1);
454
455 // lateral_error, lateral_error_rate, heading_error, heading_error_rate
456 // station_error, station_error_rate
457 lower_state_bound << -1.0 * max, -1.0 * max, -1.0 * M_PI, -1.0 * max,
458 -1.0 * max, -1.0 * max;
459 upper_state_bound << max, max, M_PI, max, max, max;
460
461 double mpc_start_timestamp = Clock::NowInSeconds();
462 double steer_angle_feedback = 0.0;
463 double acc_feedback = 0.0;
464 double steer_angle_ff_compensation = 0.0;
465 double unconstrained_control_diff = 0.0;
466 double control_gain_truncation_ratio = 0.0;
467 double unconstrained_control = 0.0;
468 double steer_angle_feedback_augment = 0.0;
469 const double v = injector_->vehicle_state()->linear_velocity();
470
471 std::vector<double> control_cmd(controls_, 0);
472
475 matrix_state_, lower_bound, upper_bound, lower_state_bound,
476 upper_state_bound, reference_state, mpc_max_iteration_, horizon_,
477 mpc_eps_);
478 if (!mpc_osqp.Solve(&control_cmd)) {
479 AERROR << "MPC OSQP solver failed";
480 } else {
481 ADEBUG << "MPC OSQP problem solved! ";
482 control[0](0, 0) = control_cmd.at(0);
483 control[0](1, 0) = control_cmd.at(1);
484 }
485
486 steer_angle_feedback = Wheel2SteerPct(control[0](0, 0));
487 acc_feedback = control[0](1, 0);
488 for (int i = 0; i < basic_state_size_; ++i) {
489 unconstrained_control += control_gain[0](0, i) * matrix_state_(i, 0);
490 }
491 unconstrained_control += addition_gain[0](0, 0) * v * debug->curvature();
493 unconstrained_control_diff =
494 Wheel2SteerPct(control[0](0, 0) - unconstrained_control);
495 if (fabs(unconstrained_control_diff) <= unconstrained_control_diff_limit_) {
496 steer_angle_ff_compensation =
497 Wheel2SteerPct(debug->curvature() *
498 (control_gain[0](0, 2) *
499 (lr_ - lf_ / cr_ * mass_ * v * v / wheelbase_) -
500 addition_gain[0](0, 0) * v));
501 } else {
502 control_gain_truncation_ratio = control[0](0, 0) / unconstrained_control;
503 steer_angle_ff_compensation =
504 Wheel2SteerPct(debug->curvature() *
505 (control_gain[0](0, 2) *
506 (lr_ - lf_ / cr_ * mass_ * v * v / wheelbase_) -
507 addition_gain[0](0, 0) * v) *
508 control_gain_truncation_ratio);
509 }
510 if (std::isnan(steer_angle_ff_compensation)) {
511 ADEBUG << "steer_angle_ff_compensation is nan";
512 steer_angle_ff_compensation = 0.0;
513 }
514 } else {
515 steer_angle_ff_compensation = 0.0;
516 }
517
518 double mpc_end_timestamp = Clock::NowInSeconds();
519
520 ADEBUG << "MPC core algorithm: calculation time is: "
521 << (mpc_end_timestamp - mpc_start_timestamp) * 1000 << " ms.";
522
523 if (enable_leadlag_) {
524 if (control_conf_.enable_feedback_augment_on_high_speed() ||
525 std::fabs(vehicle_state->linear_velocity()) < low_speed_bound_) {
526 steer_angle_feedback_augment =
527 leadlag_controller_.Control(-matrix_state_(0, 0), ts_) * 180 / M_PI *
529 if (std::fabs(vehicle_state->linear_velocity()) >
531 // Within the low-high speed transition window, linerly interplolate the
532 // augment control gain for "soft" control switch
533 steer_angle_feedback_augment = common::math::lerp(
534 steer_angle_feedback_augment, low_speed_bound_ - low_speed_window_,
535 0.0, low_speed_bound_, std::fabs(vehicle_state->linear_velocity()));
536 }
537 }
538 }
539
540 // TODO(QiL): evaluate whether need to add spline smoothing after the result
541 double steer_angle =
542 steer_angle_feedback + steer_angle_feedforwardterm_updated_ +
543 steer_angle_ff_compensation + steer_angle_feedback_augment;
544
545 if (FLAGS_set_steer_limit) {
546 const double steer_limit = std::atan(max_lat_acc_ * wheelbase_ /
547 (vehicle_state->linear_velocity() *
548 vehicle_state->linear_velocity())) *
549 steer_ratio_ * 180 / M_PI /
551
552 // Clamp the steer angle with steer limitations at current speed
553 double steer_angle_limited =
554 common::math::Clamp(steer_angle, -steer_limit, steer_limit);
555 steer_angle_limited = digital_filter_.Filter(steer_angle_limited);
556 steer_angle = steer_angle_limited;
557 debug->set_steer_angle_limited(steer_angle_limited);
558 }
559 steer_angle = digital_filter_.Filter(steer_angle);
560 // Clamp the steer angle to -100.0 to 100.0
561 steer_angle = common::math::Clamp(steer_angle, -100.0, 100.0);
562 cmd->set_steering_target(steer_angle);
563
564 debug->set_acceleration_cmd_closeloop(acc_feedback);
565
566 double vehicle_pitch = 0.0;
568 vehicle_pitch =
569 digital_filter_pitch_angle_.Filter(injector_->vehicle_state()->pitch());
570 } else {
571 vehicle_pitch = injector_->vehicle_state()->pitch();
572 }
573
574 if (std::isnan(vehicle_pitch)) {
575 AINFO << "pitch angle is nan.";
576 vehicle_pitch = 0;
577 }
578 debug->set_vehicle_pitch(vehicle_pitch);
579
580 double slope_offset_compensation = GRA_ACC * std::sin(vehicle_pitch);
581 if (std::isnan(slope_offset_compensation)) {
582 slope_offset_compensation = 0;
583 }
584 debug->set_slope_offset_compensation(slope_offset_compensation);
585
586 double acceleration_cmd =
587 acc_feedback + debug->acceleration_reference() +
588 control_conf_.enable_slope_offset() * debug->slope_offset_compensation();
589 // TODO(QiL): add pitch angle feed forward to accommodate for 3D control
590
591 GetPathRemain(planning_published_trajectory, debug);
592 // TODO(Yu): study the necessity of path_remain and add it to MPC if needed
593 // At near-stop stage, replace the brake control command with the standstill
594 // acceleration if the former is even softer than the latter
595 if ((planning_published_trajectory->trajectory_type() ==
597 (planning_published_trajectory->trajectory_type() ==
599 (planning_published_trajectory->trajectory_type() ==
601 if (control_conf_.use_preview_reference_check() &&
602 (std::fabs(debug->preview_acceleration_reference()) <=
603 FLAGS_max_acceleration_when_stopped) &&
604 std::fabs(debug->preview_speed_reference()) <=
606 debug->set_is_full_stop(true);
607 ADEBUG << "Into full stop within preview acc and reference speed, "
608 << "is_full_stop is " << debug->is_full_stop();
609 }
610 if (std::abs(debug->path_remain()) < FLAGS_max_acceleration_when_stopped) {
611 debug->set_is_full_stop(true);
612 ADEBUG << "Into full stop within path remain, "
613 << "is_full_stop is " << debug->is_full_stop();
614 }
615 }
616
617 if (debug->is_full_stop()) {
618 acceleration_cmd =
620 ? std::max(acceleration_cmd, standstill_acceleration_)
621 : std::min(acceleration_cmd, standstill_acceleration_);
622 Reset();
623 }
624
625 debug->set_acceleration_cmd(acceleration_cmd);
626
628 control_conf_.acc_lookup_pid_conf());
629
630 double acceleration_lookup_error =
631 acceleration_cmd - debug->acceleration_vrf();
632 double acceleration_lookup_offset = 0.0;
633
635 acceleration_lookup_offset = acceleration_lookup_pid_controller_.Control(
636 acceleration_lookup_error, ts_);
637 } else {
638 acceleration_lookup_offset = 0.0;
639 }
640
641 double acceleration_lookup = acceleration_lookup_offset + acceleration_cmd;
642
643 debug->set_acceleration_lookup_offset(acceleration_lookup_offset);
644
645 debug->set_acceleration_lookup(acceleration_lookup);
646
647 double calibration_value = 0.0;
648 if (FLAGS_use_preview_speed_for_table) {
649 calibration_value = control_interpolation_->Interpolate(
650 std::make_pair(debug->preview_speed_reference(), acceleration_lookup));
651 } else {
652 calibration_value = control_interpolation_->Interpolate(std::make_pair(
653 injector_->vehicle_state()->linear_velocity(), acceleration_lookup));
654 }
655
656 debug->set_calibration_value(calibration_value);
657
658 double throttle_cmd = 0.0;
659 double brake_cmd = 0.0;
660 if (acceleration_cmd >= 0) {
661 if (calibration_value >= 0) {
662 throttle_cmd = std::max(calibration_value, throttle_lowerbound_);
663 } else {
664 throttle_cmd = throttle_lowerbound_;
665 }
666 brake_cmd = 0.0;
667 } else {
668 throttle_cmd = 0.0;
669 if (calibration_value >= 0) {
670 brake_cmd = brake_lowerbound_;
671 } else {
672 brake_cmd = std::max(-calibration_value, brake_lowerbound_);
673 }
674 }
675
676 cmd->set_steering_rate(FLAGS_steer_angle_rate);
677 // if the car is driven by acceleration, disgard the cmd->throttle and brake
678 cmd->set_throttle(throttle_cmd);
679 cmd->set_brake(brake_cmd);
680 cmd->set_acceleration(acceleration_cmd);
681
682 debug->set_heading(vehicle_state->heading());
683 debug->set_steering_position(chassis->steering_percentage());
684 debug->set_steer_angle(steer_angle);
685 debug->set_steer_angle_feedforward(steer_angle_feedforwardterm_updated_);
686 debug->set_steer_angle_feedforward_compensation(steer_angle_ff_compensation);
687 debug->set_steer_unconstrained_control_diff(unconstrained_control_diff);
688 debug->set_steer_angle_feedback(steer_angle_feedback);
689 debug->set_steering_position(chassis->steering_percentage());
690 debug->set_steer_angle_feedback_augment(steer_angle_feedback_augment);
691
692 if (std::fabs(vehicle_state->linear_velocity()) <=
695 cmd->set_gear_location(planning_published_trajectory->gear());
696 } else {
697 cmd->set_gear_location(chassis->gear_location());
698 }
699
700 ProcessLogs(debug, chassis);
701 return Status::OK();
702}
703
709
711 ADEBUG << "Control calibration table size is "
712 << calibration_table_.calibration_size();
714 for (const auto &calibration : calibration_table_.calibration()) {
715 xyz.push_back(std::make_tuple(calibration.speed(),
716 calibration.acceleration(),
717 calibration.command()));
718 }
721 << "Fail to init control calibration table";
722}
723
725 const auto &com = injector_->vehicle_state()->ComputeCOMPosition(lr_);
726 ComputeLateralErrors(com.x(), com.y(), injector_->vehicle_state()->heading(),
727 injector_->vehicle_state()->linear_velocity(),
728 injector_->vehicle_state()->angular_velocity(),
729 injector_->vehicle_state()->linear_acceleration(),
730 trajectory_analyzer_, debug);
731
732 // State matrix update;
733 // matrix_state_(0, 0) = debug->lateral_error();
734 matrix_state_(1, 0) = debug->lateral_error_rate();
735 // matrix_state_(2, 0) = debug->heading_error();
736 matrix_state_(3, 0) = debug->heading_error_rate();
737 matrix_state_(4, 0) = debug->station_error();
738 matrix_state_(5, 0) = debug->speed_error();
739 // State matrix update;
740 // First four elements are fixed;
742 matrix_state_(0, 0) = debug->lateral_error_feedback();
743 matrix_state_(2, 0) = debug->heading_error_feedback();
744 } else {
745 matrix_state_(0, 0) = debug->lateral_error();
746 matrix_state_(2, 0) = debug->heading_error();
747 }
748}
749
751 const double v = std::max(injector_->vehicle_state()->linear_velocity(),
753 matrix_a_(1, 1) = matrix_a_coeff_(1, 1) / v;
754 matrix_a_(1, 3) = matrix_a_coeff_(1, 3) / v;
755 matrix_a_(3, 1) = matrix_a_coeff_(3, 1) / v;
756 matrix_a_(3, 3) = matrix_a_coeff_(3, 3) / v;
757
758 Matrix matrix_i = Matrix::Identity(matrix_a_.cols(), matrix_a_.cols());
759 matrix_ad_ = (matrix_i - ts_ * 0.5 * matrix_a_).inverse() *
760 (matrix_i + ts_ * 0.5 * matrix_a_);
761
762 matrix_c_(1, 0) = (lr_ * cr_ - lf_ * cf_) / mass_ / v - v;
763 matrix_c_(3, 0) = -(lf_ * lf_ * cf_ + lr_ * lr_ * cr_) / iz_ / v;
765}
766
768 const double v = injector_->vehicle_state()->linear_velocity();
769 const double kv =
770 lr_ * mass_ / 2 / cf_ / wheelbase_ - lf_ * mass_ / 2 / cr_ / wheelbase_;
771
772 if (control_conf_.use_kinematic_model() &&
773 injector_->vehicle_state()->gear() == canbus::Chassis::GEAR_REVERSE) {
776 } else {
778 wheelbase_ * debug->curvature() + kv * v * v * debug->curvature());
779 }
780}
781
783 const double x, const double y, const double theta, const double linear_v,
784 const double angular_v, const double linear_a,
785 const TrajectoryAnalyzer &trajectory_analyzer, SimpleMPCDebug *debug) {
786 const auto matched_point =
787 trajectory_analyzer.QueryNearestPointByPosition(x, y);
788
789 const double dx = x - matched_point.path_point().x();
790 const double dy = y - matched_point.path_point().y();
791
792 const double cos_matched_theta = std::cos(matched_point.path_point().theta());
793 const double sin_matched_theta = std::sin(matched_point.path_point().theta());
794 // d_error = cos_matched_theta * dy - sin_matched_theta * dx;
795 double lateral_error = cos_matched_theta * dy - sin_matched_theta * dx;
796 if (control_conf_.enable_navigation_mode_error_filter()) {
797 lateral_error = lateral_error_filter_.Update(lateral_error);
798 }
799 debug->set_lateral_error(lateral_error);
800
801 // matched_theta = matched_point.path_point().theta();
802 debug->set_ref_heading(matched_point.path_point().theta());
803 double delta_theta =
805 if (control_conf_.enable_navigation_mode_error_filter()) {
806 delta_theta = heading_error_filter_.Update(delta_theta);
807 }
808 debug->set_heading_error(delta_theta);
809
811 // Within the low-high speed transition window, linerly interplolate the
812 // lookahead/lookback station for "soft" prediction window switch
813 double lookahead_station = 0.0;
814 double lookback_station = 0.0;
815 if (std::fabs(linear_v) >= low_speed_bound_) {
816 lookahead_station = lookahead_station_high_speed_;
817 lookback_station = lookback_station_high_speed_;
818 } else if (std::fabs(linear_v) < low_speed_bound_ - low_speed_window_) {
819 lookahead_station = lookahead_station_low_speed_;
820 lookback_station = lookback_station_low_speed_;
821 } else {
822 lookahead_station = common::math::lerp(
824 lookahead_station_high_speed_, low_speed_bound_, std::fabs(linear_v));
825 lookback_station = common::math::lerp(
827 lookback_station_high_speed_, low_speed_bound_, std::fabs(linear_v));
828 }
829
830 // Estimate the heading error with look-ahead/look-back windows as feedback
831 // signal for special driving scenarios
832 if (injector_->vehicle_state()->gear() == canbus::Chassis::GEAR_REVERSE) {
833 heading_error_feedback = delta_theta;
834 } else {
835 auto lookahead_point =
836 trajectory_analyzer.QueryNearestPointByRelativeTime(
837 matched_point.relative_time() +
838 lookahead_station /
839 (std::max(std::fabs(linear_v), 0.1) * std::cos(delta_theta)));
841 delta_theta + matched_point.path_point().theta() -
842 lookahead_point.path_point().theta());
843 }
844 debug->set_heading_error_feedback(heading_error_feedback);
845 // Estimate the lateral error with look-ahead/look-back windows as feedback
846 // signal for special driving scenarios
847 if (injector_->vehicle_state()->gear() == canbus::Chassis::GEAR_REVERSE) {
849 lateral_error - lookback_station * std::sin(delta_theta);
850 } else {
852 lateral_error + lookahead_station * std::sin(delta_theta);
853 }
854 debug->set_lateral_error_feedback(lateral_error_feedback);
855 }
856
857 const double sin_delta_theta = std::sin(delta_theta);
858 // d_error_dot = chassis_v * sin_delta_theta;
859 double lateral_error_dot = linear_v * sin_delta_theta;
860 double lateral_error_dot_dot = linear_a * sin_delta_theta;
861 if (FLAGS_reverse_heading_control) {
862 if (injector_->vehicle_state()->gear() == canbus::Chassis::GEAR_REVERSE) {
863 lateral_error_dot = -lateral_error_dot;
864 lateral_error_dot_dot = -lateral_error_dot_dot;
865 }
866 }
867
868 debug->set_lateral_error_rate(lateral_error_dot);
869 debug->set_lateral_acceleration(lateral_error_dot_dot);
870 debug->set_lateral_jerk(
873
874 // matched_kappa = matched_point.path_point().kappa();
875 debug->set_curvature(matched_point.path_point().kappa());
876 // theta_error = delta_theta;
877 debug->set_heading_error(delta_theta);
878 // theta_error_dot = angular_v - matched_point.path_point().kappa() *
879 // matched_point.v();
880 // debug->set_heading_rate(angular_v);
881 if (injector_->vehicle_state()->gear() == canbus::Chassis::GEAR_REVERSE) {
882 debug->set_heading_rate(-angular_v);
883 } else {
884 debug->set_heading_rate(angular_v);
885 }
886 debug->set_ref_heading_rate(debug->curvature() * matched_point.v());
887 debug->set_heading_error_rate(debug->heading_rate() -
888 debug->ref_heading_rate());
889
890 debug->set_heading_acceleration(
892 debug->set_ref_heading_acceleration(
894 debug->set_heading_error_acceleration(debug->heading_acceleration() -
895 debug->ref_heading_acceleration());
898
899 debug->set_heading_jerk(
901 debug->set_ref_heading_jerk(
903 ts_);
904 debug->set_heading_error_jerk(debug->heading_jerk() -
905 debug->ref_heading_jerk());
908}
909
911 const TrajectoryAnalyzer *trajectory_analyzer, SimpleMPCDebug *debug) {
912 // the decomposed vehicle motion onto Frenet frame
913 // s: longitudinal accumulated distance along reference trajectory
914 // s_dot: longitudinal velocity along reference trajectory
915 // d: lateral distance w.r.t. reference trajectory
916 // d_dot: lateral distance change rate, i.e. dd/dt
917 double s_matched = 0.0;
918 double s_dot_matched = 0.0;
919 double d_matched = 0.0;
920 double d_dot_matched = 0.0;
921
922 const auto matched_point = trajectory_analyzer->QueryMatchedPathPoint(
923 injector_->vehicle_state()->x(), injector_->vehicle_state()->y());
924
925 trajectory_analyzer->ToTrajectoryFrame(
926 injector_->vehicle_state()->x(), injector_->vehicle_state()->y(),
927 injector_->vehicle_state()->heading(),
928 injector_->vehicle_state()->linear_velocity(), matched_point, &s_matched,
929 &s_dot_matched, &d_matched, &d_dot_matched);
930
931 const double current_control_time = Clock::NowInSeconds();
932
933 TrajectoryPoint reference_point =
934 trajectory_analyzer->QueryNearestPointByAbsoluteTime(
935 current_control_time);
936
937 ADEBUG << "matched point:" << matched_point.DebugString();
938 ADEBUG << "reference point:" << reference_point.DebugString();
939
940 const double linear_v = injector_->vehicle_state()->linear_velocity();
941 const double linear_a = injector_->vehicle_state()->linear_acceleration();
942 double heading_error = common::math::NormalizeAngle(
943 injector_->vehicle_state()->heading() - matched_point.theta());
944 double lon_speed = linear_v * std::cos(heading_error);
945 double lon_acceleration = linear_a * std::cos(heading_error);
946 double one_minus_kappa_lat_error = 1 - reference_point.path_point().kappa() *
947 linear_v * std::sin(heading_error);
948
949 debug->set_station_reference(reference_point.path_point().s());
950 debug->set_station_feedback(s_matched); // current station
951 debug->set_station_error(reference_point.path_point().s() - s_matched);
952 debug->set_speed_reference(reference_point.v());
953 debug->set_speed_feedback(lon_speed); // current speed
954 debug->set_speed_error(reference_point.v() - s_dot_matched);
955 debug->set_acceleration_reference(reference_point.a());
956 debug->set_acceleration_feedback(lon_acceleration);
957 debug->set_acceleration_error(reference_point.a() -
958 lon_acceleration / one_minus_kappa_lat_error);
959 double jerk_reference =
961 ts_;
962 double lon_jerk =
964 debug->set_jerk_reference(jerk_reference);
965 debug->set_jerk_feedback(lon_jerk);
966 debug->set_jerk_error(jerk_reference - lon_jerk / one_minus_kappa_lat_error);
969}
970
972 const TrajectoryAnalyzer *trajectory_analyzer, const double preview_time,
973 const double ts, SimpleMPCDebug *debug) {
974 // the decomposed vehicle motion onto Frenet frame
975 // s: longitudinal accumulated distance along reference trajectory
976 // s_dot: longitudinal velocity along reference trajectory
977 // d: lateral distance w.r.t. reference trajectory
978 // d_dot: lateral distance change rate, i.e. dd/dt
979 double s_matched = 0.0;
980 double s_dot_matched = 0.0;
981 double d_matched = 0.0;
982 double d_dot_matched = 0.0;
983
984 auto vehicle_state = injector_->vehicle_state();
985 auto matched_point = trajectory_analyzer->QueryMatchedPathPoint(
986 vehicle_state->x(), vehicle_state->y());
987
988 trajectory_analyzer->ToTrajectoryFrame(
989 vehicle_state->x(), vehicle_state->y(), vehicle_state->heading(),
990 vehicle_state->linear_velocity(), matched_point, &s_matched,
991 &s_dot_matched, &d_matched, &d_dot_matched);
992
993 // double current_control_time = Time::Now().ToSecond();
994 double current_control_time = ::apollo::cyber::Clock::NowInSeconds();
995 double preview_control_time = current_control_time + preview_time;
996
997 TrajectoryPoint reference_point =
998 trajectory_analyzer->QueryNearestPointByAbsoluteTime(
999 current_control_time);
1000 TrajectoryPoint preview_point =
1001 trajectory_analyzer->QueryNearestPointByAbsoluteTime(
1002 preview_control_time);
1003
1004 debug->mutable_current_matched_point()->mutable_path_point()->set_x(
1005 matched_point.x());
1006 debug->mutable_current_matched_point()->mutable_path_point()->set_y(
1007 matched_point.y());
1008 debug->mutable_current_reference_point()->mutable_path_point()->set_x(
1009 reference_point.path_point().x());
1010 debug->mutable_current_reference_point()->mutable_path_point()->set_y(
1011 reference_point.path_point().y());
1012 debug->mutable_preview_reference_point()->mutable_path_point()->set_x(
1013 preview_point.path_point().x());
1014 debug->mutable_preview_reference_point()->mutable_path_point()->set_y(
1015 preview_point.path_point().y());
1016
1017 ADEBUG << "matched point:" << matched_point.DebugString();
1018 ADEBUG << "reference point:" << reference_point.DebugString();
1019 ADEBUG << "preview point:" << preview_point.DebugString();
1020
1021 double heading_error = common::math::NormalizeAngle(vehicle_state->heading() -
1022 matched_point.theta());
1023 double lon_speed = vehicle_state->linear_velocity() * std::cos(heading_error);
1024 double lon_acceleration =
1025 vehicle_state->linear_acceleration() * std::cos(heading_error);
1026 double one_minus_kappa_lat_error = 1 - reference_point.path_point().kappa() *
1027 vehicle_state->linear_velocity() *
1028 std::sin(heading_error);
1029
1030 debug->set_station_reference(reference_point.path_point().s());
1031 debug->set_station_feedback(s_matched);
1032 debug->set_station_error(reference_point.path_point().s() - s_matched);
1033 debug->set_speed_reference(reference_point.v());
1034 debug->set_speed_feedback(lon_speed);
1035 debug->set_speed_error(reference_point.v() - s_dot_matched);
1036 debug->set_acceleration_reference(reference_point.a());
1037 debug->set_acceleration_feedback(lon_acceleration);
1038 debug->set_acceleration_vrf(vehicle_state->linear_acceleration());
1039 debug->set_acceleration_error(reference_point.a() -
1040 lon_acceleration / one_minus_kappa_lat_error);
1041 double jerk_reference =
1043 double lon_jerk =
1045 debug->set_jerk_reference(jerk_reference);
1046 debug->set_jerk_feedback(lon_jerk);
1047 debug->set_jerk_error(jerk_reference - lon_jerk / one_minus_kappa_lat_error);
1051
1052 debug->set_preview_station_error(preview_point.path_point().s() - s_matched);
1053 debug->set_preview_speed_error(preview_point.v() - s_dot_matched);
1054 debug->set_preview_speed_reference(preview_point.v());
1055 debug->set_preview_acceleration_reference(preview_point.a());
1056}
1057
1058// TODO(all): Refactor and simplify
1060 const planning::ADCTrajectory *planning_published_trajectory,
1061 SimpleMPCDebug *debug) {
1062 int stop_index = 0;
1063 static constexpr double kSpeedThreshold = 1e-3;
1064 static constexpr double kForwardAccThreshold = -1e-2;
1065 static constexpr double kBackwardAccThreshold = 1e-1;
1066 static constexpr double kParkingSpeed = 0.1;
1067
1068 if (planning_published_trajectory->gear() == canbus::Chassis::GEAR_DRIVE) {
1069 while (stop_index <
1070 planning_published_trajectory->trajectory_point_size()) {
1071 auto &current_trajectory_point =
1072 planning_published_trajectory->trajectory_point(stop_index);
1073 if (fabs(current_trajectory_point.v()) < kSpeedThreshold &&
1074 current_trajectory_point.a() > kForwardAccThreshold &&
1075 current_trajectory_point.a() < 0.0) {
1076 break;
1077 }
1078 ++stop_index;
1079 }
1080 } else {
1081 while (stop_index <
1082 planning_published_trajectory->trajectory_point_size()) {
1083 auto &current_trajectory_point =
1084 planning_published_trajectory->trajectory_point(stop_index);
1085 if (current_trajectory_point.v() > -kSpeedThreshold &&
1086 current_trajectory_point.a() < kBackwardAccThreshold &&
1087 current_trajectory_point.a() > 0.0) {
1088 break;
1089 }
1090 ++stop_index;
1091 }
1092 }
1093 ADEBUG << "stop_index is, " << stop_index;
1094 if (stop_index == planning_published_trajectory->trajectory_point_size()) {
1095 --stop_index;
1096 if (fabs(planning_published_trajectory->trajectory_point(stop_index).v()) <
1097 kParkingSpeed) {
1098 ADEBUG << "the last point is selected as parking point";
1099 } else {
1100 ADEBUG << "the last point found in path and speed > speed_deadzone";
1101 }
1102 }
1103 debug->set_path_remain(
1104 planning_published_trajectory->trajectory_point(stop_index)
1105 .path_point()
1106 .s() -
1107 debug->station_feedback());
1108}
1109
1110} // namespace control
1111} // namespace apollo
void set_coefficients(const std::vector< double > &denominators, const std::vector< double > &numerators)
set denominators and numerators
double Filter(const double x_insert)
Processes a new measurement with the filter.
The MeanFilter class is used to smoothen a series of noisy numbers, such as sensor data or the output...
Definition mean_filter.h:45
double Update(const double measurement)
Processes a new measurement in amortized constant time.
A general class to denote the return status of an API call.
Definition status.h:43
static Status OK()
generate a success status.
Definition status.h:60
@Brief This is a helper class that can load vehicle configurations.
bool Solve(std::vector< double > *control_cmd)
Definition mpc_osqp.cc:281
bool LoadCalibrationTable(calibration_table *calibration_table_conf)
std::vector< std::pair< double, double > > DataType
linear interpolation from key (double, double) to one double value.
std::vector< std::tuple< double, double, double > > DataType
void Init(const LeadlagConf &leadlag_conf, const double dt)
initialize lead/lag controller
virtual double Control(const double error, const double dt)
compute control value based on the error
PIDController acceleration_lookup_pid_controller_
TrajectoryAnalyzer trajectory_analyzer_
void FeedforwardUpdate(SimpleMPCDebug *debug)
common::Status ComputeControlCommand(const localization::LocalizationEstimate *localization, const canbus::Chassis *chassis, const planning::ADCTrajectory *trajectory, ControlCommand *cmd) override
compute steering target and throttle/ brake based on current vehicle status and target trajectory
void GetPathRemain(const planning::ADCTrajectory *planning_published_trajectory, SimpleMPCDebug *debug)
void ProcessLogs(const SimpleMPCDebug *debug, const canbus::Chassis *chassis)
void ComputeLateralErrors(const double x, const double y, const double theta, const double linear_v, const double angular_v, const double linear_a, const TrajectoryAnalyzer &trajectory_analyzer, SimpleMPCDebug *debug)
void UpdateMatrix(SimpleMPCDebug *debug)
std::unique_ptr< Interpolation1D > heading_err_interpolation_
LeadlagController leadlag_controller_
common::MeanFilter lateral_error_filter_
std::unique_ptr< Interpolation1D > feedforwardterm_interpolation_
std::unique_ptr< Interpolation2D > control_interpolation_
void Stop() override
stop MPC controller
std::unique_ptr< Interpolation1D > lat_err_interpolation_
common::DigitalFilter digital_filter_pitch_angle_
std::unique_ptr< Interpolation1D > steer_weight_interpolation_
calibration_table calibration_table_
double Wheel2SteerPct(const double wheel_angle)
common::VehicleParam vehicle_param_
common::MeanFilter heading_error_filter_
common::Status Reset() override
reset MPC Controller
std::shared_ptr< DependencyInjector > injector_
std::string Name() const override
MPC controller name
virtual ~MPCController()
destructor
common::Status Init(std::shared_ptr< DependencyInjector > injector) override
initialize MPC Controller
common::DigitalFilter digital_filter_
void UpdateState(SimpleMPCDebug *debug)
void ComputeLongitudinalErrors(const TrajectoryAnalyzer *trajectory, SimpleMPCDebug *debug)
void Init(const PidConf &pid_conf)
initialize pid controller
void SetPID(const PidConf &pid_conf)
set pid controller coefficients for the proportional, integral, and derivative
virtual double Control(const double error, const double dt)
compute control value based on the error
process point query and conversion related to trajectory
common::TrajectoryPoint QueryNearestPointByPosition(const double x, const double y) const
query a point of trajectory that its position is closest to the given position.
void TrajectoryTransformToCOM(const double rear_to_com_distance)
Transform the current trajectory points to the center of mass(COM) of the vehicle,...
common::PathPoint QueryMatchedPathPoint(const double x, const double y) const
query a point on trajectory that its position is closest to the given position.
common::TrajectoryPoint QueryNearestPointByAbsoluteTime(const double t) const
query a point of trajectory that its absolute time is closest to the give time.
void ToTrajectoryFrame(const double x, const double y, const double theta, const double v, const common::PathPoint &matched_point, double *ptr_s, double *ptr_s_dot, double *ptr_d, double *ptr_d_dot) const
convert a position with theta and speed to trajectory frame,
common::TrajectoryPoint QueryNearestPointByRelativeTime(const double t) const
query a point of trajectory that its relative time is closest to the give time.
a singleton clock that can be used to get the current timestamp.
Definition clock.h:39
static double NowInSeconds()
gets the current time in second.
Definition clock.cc:56
Linear interpolation functions.
#define ACHECK(cond)
Definition log.h:80
#define ADEBUG
Definition log.h:41
#define AERROR
Definition log.h:44
#define AINFO
Definition log.h:42
Math-related util functions.
Defines the MPCController class.
T lerp(const T &x0, const double t0, const T &x1, const double t1, const double t)
Linear interpolation between two points of type T.
T Clamp(const T value, T bound1, T bound2)
Clamp a value between two bounds.
Definition math_utils.h:155
double NormalizeAngle(const double angle)
Normalize angle to [-PI, PI).
Definition math_utils.cc:53
void LpfCoefficients(const double ts, const double cutoff_freq, std::vector< double > *denominators, std::vector< double > *numerators)
Get low-pass coefficients for digital filter.
constexpr double GRA_ACC
class register implement
Definition arena_queue.h:37
optional GearPosition gear_location
optional float steering_percentage
Definition chassis.proto:88
optional double preview_acceleration_reference
repeated ControlCalibrationInfo calibration
repeated apollo::common::TrajectoryPoint trajectory_point
optional TrajectoryType trajectory_type
optional apollo::canbus::Chassis::GearPosition gear