Skip to content

Commit

Permalink
Merge pull request #868 from tier4/feat/pid-control-improvement
Browse files Browse the repository at this point in the history
feat(pid_longitudinal_controller): several bug fix
  • Loading branch information
takayuki5168 authored Sep 26, 2023
2 parents 6ca438c + d3621a8 commit bacf767
Show file tree
Hide file tree
Showing 5 changed files with 44 additions and 82 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -66,11 +66,6 @@ double getPitchByPose(const Quaternion & quaternion);
double getPitchByTraj(
const Trajectory & trajectory, const size_t closest_idx, const double wheel_base);

/**
* @brief calculate elevation angle
*/
double calcElevationAngle(const TrajectoryPoint & p_from, const TrajectoryPoint & p_to);

/**
* @brief calculate vehicle pose after time delay by moving the vehicle at current velocity and
* acceleration for delayed time
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -362,7 +362,7 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
* @param [in] current_vel current velocity of the vehicle
*/
double applyVelocityFeedback(
const Motion target_motion, const double dt, const double current_vel);
const Motion target_motion, const double dt, const double current_vel, const Shift & shift);

/**
* @brief update variables for debugging about pitch
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -91,41 +91,22 @@ double getPitchByTraj(
return 0.0;
}

for (size_t i = nearest_idx + 1; i < trajectory.points.size(); ++i) {
const double dist = tier4_autoware_utils::calcDistance2d(
trajectory.points.at(nearest_idx), trajectory.points.at(i));
if (dist > wheel_base) {
// calculate pitch from trajectory between rear wheel (nearest) and front center (i)
return calcElevationAngle(trajectory.points.at(nearest_idx), trajectory.points.at(i));
const auto [prev_idx, next_idx] = [&]() {
for (size_t i = nearest_idx + 1; i < trajectory.points.size(); ++i) {
const double dist = tier4_autoware_utils::calcDistance2d(
trajectory.points.at(nearest_idx), trajectory.points.at(i));
if (dist > wheel_base) {
// calculate pitch from trajectory between rear wheel (nearest) and front center (i)
return std::make_pair(nearest_idx, i);
}
}
}

// close to goal
for (size_t i = trajectory.points.size() - 1; i > 0; --i) {
const double dist =
tier4_autoware_utils::calcDistance2d(trajectory.points.back(), trajectory.points.at(i));

if (dist > wheel_base) {
// calculate pitch from trajectory
// between wheelbase behind the end of trajectory (i) and the end of trajectory (back)
return calcElevationAngle(trajectory.points.at(i), trajectory.points.back());
}
}
// NOTE: The ego pose is close to the goal.
return std::make_pair(
std::min(nearest_idx, trajectory.points.size() - 2), trajectory.points.size() - 1);
}();

// calculate pitch from trajectory between the beginning and end of trajectory
return calcElevationAngle(trajectory.points.at(0), trajectory.points.back());
}

double calcElevationAngle(const TrajectoryPoint & p_from, const TrajectoryPoint & p_to)
{
const double dx = p_from.pose.position.x - p_to.pose.position.x;
const double dy = p_from.pose.position.y - p_to.pose.position.y;
const double dz = p_from.pose.position.z - p_to.pose.position.z;

const double dxy = std::max(std::hypot(dx, dy), std::numeric_limits<double>::epsilon());
const double pitch = std::atan2(dz, dxy);

return pitch;
return tier4_autoware_utils::calcElevationAngle(
trajectory.points.at(prev_idx).pose.position, trajectory.points.at(next_idx).pose.position);
}

Pose calcPoseAfterTimeDelay(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -526,10 +526,8 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d
RCLCPP_INFO_SKIPFIRST_THROTTLE(node_->get_logger(), *node_->get_clock(), 5000, "%s", s);
};

// if current operation mode is not autonomous mode, then change state to stopped
if (m_current_operation_mode.mode != OperationModeState::AUTONOMOUS) {
return changeState(ControlState::STOPPED);
}
const bool is_under_control = m_current_operation_mode.is_autoware_control_enabled &&
m_current_operation_mode.mode == OperationModeState::AUTONOMOUS;

// transit state
// in DRIVE state
Expand All @@ -538,6 +536,12 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d
return changeState(ControlState::EMERGENCY);
}

if (!is_under_control && stopped_condition && keep_stopped_condition) {
// NOTE: When the ego is stopped on manual driving, since the driving state may transit to
// autonomous, keep_stopped_condition should be checked.
return changeState(ControlState::STOPPED);
}

if (m_enable_smooth_stop) {
if (stopping_condition) {
// predictions after input time delay
Expand Down Expand Up @@ -604,8 +608,14 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d

// in EMERGENCY state
if (m_control_state == ControlState::EMERGENCY) {
if (stopped_condition && !emergency_condition) {
return changeState(ControlState::STOPPED);
if (!emergency_condition) {
if (stopped_condition) {
return changeState(ControlState::STOPPED);
}
if (!is_under_control) {
// NOTE: On manual driving, no need stopping to exit the emergency.
return changeState(ControlState::DRIVE);
}
}
return;
}
Expand Down Expand Up @@ -639,7 +649,8 @@ PidLongitudinalController::Motion PidLongitudinalController::calcCtrlCmd(
m_debug_values.setValues(DebugValues::TYPE::PREDICTED_VEL, pred_vel_in_target);

raw_ctrl_cmd.vel = target_motion.vel;
raw_ctrl_cmd.acc = applyVelocityFeedback(target_motion, control_data.dt, pred_vel_in_target);
raw_ctrl_cmd.acc =
applyVelocityFeedback(target_motion, control_data.dt, pred_vel_in_target, control_data.shift);
RCLCPP_DEBUG(
node_->get_logger(),
"[feedback control] vel: %3.3f, acc: %3.3f, dt: %3.3f, v_curr: %3.3f, v_ref: %3.3f "
Expand Down Expand Up @@ -813,7 +824,7 @@ double PidLongitudinalController::applySlopeCompensation(
const double pitch_limited = std::min(std::max(pitch, m_min_pitch_rad), m_max_pitch_rad);

// Acceleration command is always positive independent of direction (= shift) when car is running
double sign = (shift == Shift::Forward) ? -1 : (shift == Shift::Reverse ? 1 : 0);
double sign = (shift == Shift::Forward) ? 1.0 : (shift == Shift::Reverse ? -1.0 : 0);
double compensated_acc = input_acc + sign * 9.81 * std::sin(pitch_limited);
return compensated_acc;
}
Expand Down Expand Up @@ -915,14 +926,16 @@ double PidLongitudinalController::predictedVelocityInTargetPoint(
}

double PidLongitudinalController::applyVelocityFeedback(
const Motion target_motion, const double dt, const double current_vel)
const Motion target_motion, const double dt, const double current_vel, const Shift & shift)
{
const double current_vel_abs = std::fabs(current_vel);
const double target_vel_abs = std::fabs(target_motion.vel);
const bool is_under_control = m_current_operation_mode.mode == OperationModeState::AUTONOMOUS;
// NOTE: Acceleration command is always positive even if the ego drives backward.
const double vel_sign = (shift == Shift::Forward) ? 1.0 : (shift == Shift::Reverse ? -1.0 : 0.0);
const double diff_vel = (target_motion.vel - current_vel) * vel_sign;
const bool is_under_control = m_current_operation_mode.is_autoware_control_enabled &&
m_current_operation_mode.mode == OperationModeState::AUTONOMOUS;
const bool enable_integration =
(current_vel_abs > m_current_vel_threshold_pid_integrate) && is_under_control;
const double error_vel_filtered = m_lpf_vel_error->filter(target_vel_abs - current_vel_abs);
(std::abs(current_vel) > m_current_vel_threshold_pid_integrate) && is_under_control;
const double error_vel_filtered = m_lpf_vel_error->filter(diff_vel);

std::vector<double> pid_contributions(3);
const double pid_acc =
Expand All @@ -935,8 +948,8 @@ double PidLongitudinalController::applyVelocityFeedback(
// deviation will be bigger.
constexpr double ff_scale_max = 2.0; // for safety
constexpr double ff_scale_min = 0.5; // for safety
const double ff_scale =
std::clamp(current_vel_abs / std::max(target_vel_abs, 0.1), ff_scale_min, ff_scale_max);
const double ff_scale = std::clamp(
std::abs(current_vel) / std::max(std::abs(target_motion.vel), 0.1), ff_scale_min, ff_scale_max);
const double ff_acc = target_motion.acc * ff_scale;

const double feedback_acc = ff_acc + pid_acc;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -158,33 +158,6 @@ TEST(TestLongitudinalControllerUtils, getPitchByTraj)
std::atan2(0.5, 1));
}

TEST(TestLongitudinalControllerUtils, calcElevationAngle)
{
using autoware_auto_planning_msgs::msg::TrajectoryPoint;
TrajectoryPoint p_from;
p_from.pose.position.x = 0.0;
p_from.pose.position.y = 0.0;
TrajectoryPoint p_to;
p_to.pose.position.x = 1.0;
p_to.pose.position.y = 0.0;
EXPECT_DOUBLE_EQ(longitudinal_utils::calcElevationAngle(p_from, p_to), 0.0);
p_to.pose.position.x = 1.0;
p_to.pose.position.z = 1.0;
EXPECT_DOUBLE_EQ(longitudinal_utils::calcElevationAngle(p_from, p_to), -M_PI_4);
p_to.pose.position.x = -1.0;
p_to.pose.position.z = 1.0;
EXPECT_DOUBLE_EQ(longitudinal_utils::calcElevationAngle(p_from, p_to), -M_PI_4);
p_to.pose.position.x = 0.0;
p_to.pose.position.z = 1.0;
EXPECT_DOUBLE_EQ(longitudinal_utils::calcElevationAngle(p_from, p_to), -M_PI_2);
p_to.pose.position.x = 1.0;
p_to.pose.position.z = -1.0;
EXPECT_DOUBLE_EQ(longitudinal_utils::calcElevationAngle(p_from, p_to), M_PI_4);
p_to.pose.position.x = -1.0;
p_to.pose.position.z = -1.0;
EXPECT_DOUBLE_EQ(longitudinal_utils::calcElevationAngle(p_from, p_to), M_PI_4);
}

TEST(TestLongitudinalControllerUtils, calcPoseAfterTimeDelay)
{
using geometry_msgs::msg::Pose;
Expand Down

0 comments on commit bacf767

Please sign in to comment.