Skip to content

Commit b43cffb

Browse files
authored
fix(controller): revival of dry steering (autowarefoundation#7903)
* Revert "fix(autoware_mpc_lateral_controller): delete the zero speed constraint (autowarefoundation#7673)" This reverts commit 69258bd. * dry steering Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * add comments Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * add minor fix and modify unit test for dry steering Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> --------- Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
1 parent 9c559e6 commit b43cffb

File tree

5 files changed

+79
-38
lines changed

5 files changed

+79
-38
lines changed

control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc.hpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -271,7 +271,7 @@ class MPC
271271
*/
272272
std::pair<bool, VectorXd> executeOptimization(
273273
const MPCMatrix & mpc_matrix, const VectorXd & x0, const double prediction_dt,
274-
const MPCTrajectory & trajectory);
274+
const MPCTrajectory & trajectory, const double current_velocity);
275275

276276
/**
277277
* @brief Resample the trajectory with the MPC resampling time.
@@ -386,7 +386,8 @@ class MPC
386386
* @param reference_trajectory The reference trajectory.
387387
* @param current_velocity current velocity of ego.
388388
*/
389-
VectorXd calcSteerRateLimitOnTrajectory(const MPCTrajectory & trajectory) const;
389+
VectorXd calcSteerRateLimitOnTrajectory(
390+
const MPCTrajectory & trajectory, const double current_velocity) const;
390391

391392
//!< @brief logging with warn and return false
392393
template <typename... Args>

control/autoware_mpc_lateral_controller/src/mpc.cpp

+15-5
Original file line numberDiff line numberDiff line change
@@ -76,8 +76,9 @@ bool MPC::calculateMPC(
7676
const auto mpc_matrix = generateMPCMatrix(mpc_resampled_ref_trajectory, prediction_dt);
7777

7878
// solve Optimization problem
79-
const auto [success_opt, Uex] =
80-
executeOptimization(mpc_matrix, x0_delayed, prediction_dt, mpc_resampled_ref_trajectory);
79+
const auto [success_opt, Uex] = executeOptimization(
80+
mpc_matrix, x0_delayed, prediction_dt, mpc_resampled_ref_trajectory,
81+
current_kinematics.twist.twist.linear.x);
8182
if (!success_opt) {
8283
return fail_warn_throttle("optimization failed. Stop MPC.");
8384
}
@@ -543,7 +544,8 @@ MPCMatrix MPC::generateMPCMatrix(
543544
* [ -au_lim * dt ] < [uN-uN-1] < [ au_lim * dt ] (*N... DIM_U)
544545
*/
545546
std::pair<bool, VectorXd> MPC::executeOptimization(
546-
const MPCMatrix & m, const VectorXd & x0, const double prediction_dt, const MPCTrajectory & traj)
547+
const MPCMatrix & m, const VectorXd & x0, const double prediction_dt, const MPCTrajectory & traj,
548+
const double current_velocity)
547549
{
548550
VectorXd Uex;
549551

@@ -576,7 +578,7 @@ std::pair<bool, VectorXd> MPC::executeOptimization(
576578
VectorXd ub = VectorXd::Constant(DIM_U_N, m_steer_lim); // max steering angle
577579

578580
// steering angle rate limit
579-
VectorXd steer_rate_limits = calcSteerRateLimitOnTrajectory(traj);
581+
VectorXd steer_rate_limits = calcSteerRateLimitOnTrajectory(traj, current_velocity);
580582
VectorXd ubA = steer_rate_limits * prediction_dt;
581583
VectorXd lbA = -steer_rate_limits * prediction_dt;
582584
ubA(0) = m_raw_steer_cmd_prev + steer_rate_limits(0) * m_ctrl_period;
@@ -728,7 +730,8 @@ double MPC::calcDesiredSteeringRate(
728730
return steer_rate;
729731
}
730732

731-
VectorXd MPC::calcSteerRateLimitOnTrajectory(const MPCTrajectory & trajectory) const
733+
VectorXd MPC::calcSteerRateLimitOnTrajectory(
734+
const MPCTrajectory & trajectory, const double current_velocity) const
732735
{
733736
const auto interp = [&](const auto & steer_rate_limit_map, const auto & current) {
734737
std::vector<double> reference, limits;
@@ -762,6 +765,13 @@ VectorXd MPC::calcSteerRateLimitOnTrajectory(const MPCTrajectory & trajectory) c
762765
return reference.back();
763766
};
764767

768+
// When the vehicle is stopped, a large steer rate limit is used for the dry steering.
769+
constexpr double steer_rate_lim = 100.0;
770+
const bool is_vehicle_stopped = std::fabs(current_velocity) < 0.01;
771+
if (is_vehicle_stopped) {
772+
return steer_rate_lim * VectorXd::Ones(m_param.prediction_horizon);
773+
}
774+
765775
// calculate steering rate limit
766776
VectorXd steer_rate_limits = VectorXd::Zero(m_param.prediction_horizon);
767777
for (int i = 0; i < m_param.prediction_horizon; ++i) {

control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -234,6 +234,8 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
234234
// debug values
235235
DebugValues m_debug_values;
236236

237+
std::optional<bool> m_prev_keep_stopped_condition{std::nullopt};
238+
237239
std::shared_ptr<rclcpp::Time> m_last_running_time{std::make_shared<rclcpp::Time>(clock_->now())};
238240

239241
// Diagnostic

control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp

+37-26
Original file line numberDiff line numberDiff line change
@@ -599,21 +599,6 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d
599599
// NOTE: the same velocity threshold as autoware::motion_utils::searchZeroVelocity
600600
static constexpr double vel_epsilon = 1e-3;
601601

602-
// Let vehicle start after the steering is converged for control accuracy
603-
const bool keep_stopped_condition = std::fabs(current_vel) < vel_epsilon &&
604-
m_enable_keep_stopped_until_steer_convergence &&
605-
!lateral_sync_data_.is_steer_converged;
606-
if (keep_stopped_condition) {
607-
auto marker = createDefaultMarker(
608-
"map", clock_->now(), "stop_reason", 0, Marker::TEXT_VIEW_FACING,
609-
createMarkerScale(0.0, 0.0, 1.0), createMarkerColor(1.0, 1.0, 1.0, 0.999));
610-
marker.pose = autoware::universe_utils::calcOffsetPose(
611-
m_current_kinematic_state.pose.pose, m_wheel_base + m_front_overhang,
612-
m_vehicle_width / 2 + 2.0, 1.5);
613-
marker.text = "steering not\nconverged";
614-
m_pub_stop_reason_marker->publish(marker);
615-
}
616-
617602
const bool stopping_condition = stop_dist < p.stopping_state_stop_dist;
618603

619604
const bool is_stopped = std::abs(current_vel) < p.stopped_state_entry_vel &&
@@ -672,15 +657,18 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d
672657
m_under_control_starting_time =
673658
is_under_control ? std::make_shared<rclcpp::Time>(clock_->now()) : nullptr;
674659
}
660+
661+
if (m_control_state != ControlState::STOPPED) {
662+
m_prev_keep_stopped_condition = std::nullopt;
663+
}
664+
675665
// transit state
676666
// in DRIVE state
677667
if (m_control_state == ControlState::DRIVE) {
678668
if (emergency_condition) {
679669
return changeState(ControlState::EMERGENCY);
680670
}
681-
if (!is_under_control && stopped_condition && keep_stopped_condition) {
682-
// NOTE: When the ego is stopped on manual driving, since the driving state may transit to
683-
// autonomous, keep_stopped_condition should be checked.
671+
if (!is_under_control && stopped_condition) {
684672
return changeState(ControlState::STOPPED);
685673
}
686674

@@ -723,19 +711,42 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d
723711

724712
// in STOPPED state
725713
if (m_control_state == ControlState::STOPPED) {
726-
// -- debug print --
714+
// debug print
727715
if (has_nonzero_target_vel && !departure_condition_from_stopped) {
728716
debug_msg_once("target speed > 0, but departure condition is not met. Keep STOPPED.");
729717
}
730-
if (has_nonzero_target_vel && keep_stopped_condition) {
731-
debug_msg_once("target speed > 0, but keep stop condition is met. Keep STOPPED.");
732-
}
733-
// ---------------
734718

735-
if (keep_stopped_condition) {
736-
return changeState(ControlState::STOPPED);
737-
}
738719
if (departure_condition_from_stopped) {
720+
// Let vehicle start after the steering is converged for dry steering
721+
const bool current_keep_stopped_condition =
722+
std::fabs(current_vel) < vel_epsilon && !lateral_sync_data_.is_steer_converged;
723+
// NOTE: Dry steering is considered unnecessary when the steering is converged twice in a
724+
// row. This is because lateral_sync_data_.is_steer_converged is not the current but
725+
// the previous value due to the order controllers' run and sync functions.
726+
const bool keep_stopped_condition =
727+
!m_prev_keep_stopped_condition ||
728+
(current_keep_stopped_condition || *m_prev_keep_stopped_condition);
729+
m_prev_keep_stopped_condition = current_keep_stopped_condition;
730+
if (m_enable_keep_stopped_until_steer_convergence && keep_stopped_condition) {
731+
// debug print
732+
if (has_nonzero_target_vel) {
733+
debug_msg_once("target speed > 0, but keep stop condition is met. Keep STOPPED.");
734+
}
735+
736+
// publish debug marker
737+
auto marker = createDefaultMarker(
738+
"map", clock_->now(), "stop_reason", 0, Marker::TEXT_VIEW_FACING,
739+
createMarkerScale(0.0, 0.0, 1.0), createMarkerColor(1.0, 1.0, 1.0, 0.999));
740+
marker.pose = autoware::universe_utils::calcOffsetPose(
741+
m_current_kinematic_state.pose.pose, m_wheel_base + m_front_overhang,
742+
m_vehicle_width / 2 + 2.0, 1.5);
743+
marker.text = "steering not\nconverged";
744+
m_pub_stop_reason_marker->publish(marker);
745+
746+
// keep STOPPED
747+
return;
748+
}
749+
739750
m_pid_vel.reset();
740751
m_lpf_vel_error->reset(0.0);
741752
// prevent the car from taking a long time to start to move

control/autoware_trajectory_follower_node/test/test_controller_node.cpp

+22-5
Original file line numberDiff line numberDiff line change
@@ -589,11 +589,28 @@ TEST_F(FakeNodeFixture, longitudinal_check_steer_converged)
589589
traj.points.push_back(make_traj_point(0.0, 0.0, 1.0f));
590590
traj.points.push_back(make_traj_point(50.0, 0.0, 1.0f));
591591
traj.points.push_back(make_traj_point(100.0, 0.0, 1.0f));
592-
tester.traj_pub->publish(traj);
593592

594-
test_utils::waitForMessage(tester.node, this, tester.received_control_command);
593+
{ // Check if the ego can keep stopped when the steering is not converged.
594+
tester.traj_pub->publish(traj);
595+
test_utils::waitForMessage(tester.node, this, tester.received_control_command);
595596

596-
ASSERT_TRUE(tester.received_control_command);
597-
// Keep stopped state when the lateral control is not converged.
598-
EXPECT_DOUBLE_EQ(tester.cmd_msg->longitudinal.velocity, 0.0f);
597+
ASSERT_TRUE(tester.received_control_command);
598+
// Keep stopped state when the lateral control is not converged.
599+
EXPECT_DOUBLE_EQ(tester.cmd_msg->longitudinal.velocity, 0.0f);
600+
}
601+
602+
{ // Check if the ego can keep stopped after the following sequence
603+
// 1. not converged -> 2. converged -> 3. not converged
604+
tester.publish_steer_angle(0.0);
605+
tester.traj_pub->publish(traj);
606+
test_utils::waitForMessage(tester.node, this, tester.received_control_command);
607+
608+
tester.publish_steer_angle(steering_tire_angle);
609+
tester.traj_pub->publish(traj);
610+
test_utils::waitForMessage(tester.node, this, tester.received_control_command);
611+
612+
ASSERT_TRUE(tester.received_control_command);
613+
// Keep stopped state when the lateral control is not converged.
614+
EXPECT_DOUBLE_EQ(tester.cmd_msg->longitudinal.velocity, 0.0f);
615+
}
599616
}

0 commit comments

Comments
 (0)