Skip to content

Commit

Permalink
feat(pid_longitudinal_controller): improve delay and slope compensation
Browse files Browse the repository at this point in the history
Signed-off-by: Berkay Karaman <[email protected]>
  • Loading branch information
brkay54 committed Nov 10, 2023
1 parent 208ecf2 commit 5bcff34
Show file tree
Hide file tree
Showing 6 changed files with 314 additions and 188 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@

#include <cmath>
#include <limits>
#include <utility>

namespace autoware::motion::control::pid_longitudinal_controller
{
Expand Down Expand Up @@ -60,11 +61,11 @@ double getPitchByPose(const Quaternion & quaternion);
* @brief calculate pitch angle from trajectory on map
* NOTE: there is currently no z information so this always returns 0.0
* @param [in] trajectory input trajectory
* @param [in] closest_idx nearest index to current vehicle position
* @param [in] start_idx nearest index to current vehicle position
* @param [in] wheel_base length of wheel base
*/
double getPitchByTraj(
const Trajectory & trajectory, const size_t closest_idx, const double wheel_base);
const Trajectory & trajectory, const size_t start_idx, const double wheel_base);

/**
* @brief calculate vehicle pose after time delay by moving the vehicle at current velocity and
Expand All @@ -88,7 +89,7 @@ Quaternion lerpOrientation(const Quaternion & o_from, const Quaternion & o_to, c
* @param [in] point Interpolated point is nearest to this point.
*/
template <class T>
TrajectoryPoint lerpTrajectoryPoint(
std::pair<TrajectoryPoint, size_t> lerpTrajectoryPoint(
const T & points, const Pose & pose, const double max_dist, const double max_yaw)
{
TrajectoryPoint interpolated_point;
Expand All @@ -107,6 +108,8 @@ TrajectoryPoint lerpTrajectoryPoint(
points.at(i).pose.position.x, points.at(i + 1).pose.position.x, interpolate_ratio);
interpolated_point.pose.position.y = interpolation::lerp(
points.at(i).pose.position.y, points.at(i + 1).pose.position.y, interpolate_ratio);
interpolated_point.pose.position.z = interpolation::lerp(
points.at(i).pose.position.z, points.at(i + 1).pose.position.z, interpolate_ratio);
interpolated_point.pose.orientation = lerpOrientation(
points.at(i).pose.orientation, points.at(i + 1).pose.orientation, interpolate_ratio);
interpolated_point.longitudinal_velocity_mps = interpolation::lerp(
Expand All @@ -120,7 +123,7 @@ TrajectoryPoint lerpTrajectoryPoint(
points.at(i).heading_rate_rps, points.at(i + 1).heading_rate_rps, interpolate_ratio);
}

return interpolated_point;
return std::make_pair(interpolated_point, seg_idx);
}

/**
Expand All @@ -144,6 +147,17 @@ double applyDiffLimitFilter(
double applyDiffLimitFilter(
const double input_val, const double prev_val, const double dt, const double max_val,
const double min_val);

/**
* @brief calculate the projected pose after distance from the current index
* @param [in] src_idx current index
* @param [in] distance distance to project
* @param [in] trajectory reference trajectory
*/
geometry_msgs::msg::Pose findTrajectoryPoseAfterDistance(
const size_t src_idx, const double distance,
const autoware_auto_planning_msgs::msg::Trajectory & trajectory);

} // namespace longitudinal_utils
} // namespace autoware::motion::control::pid_longitudinal_controller

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -65,13 +65,25 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
double vel{0.0};
double acc{0.0};
};

struct StateAfterDelay
{
StateAfterDelay(const double velocity, const double acceleration, const double distance)
: vel(velocity), acc(acceleration), running_distance(distance)
{
}
double vel{0.0};
double acc{0.0};
double running_distance{0.0};
};
enum class Shift { Forward = 0, Reverse };

struct ControlData
{
bool is_far_from_trajectory{false};
autoware_auto_planning_msgs::msg::Trajectory interpolated_traj{};
size_t nearest_idx{0}; // nearest_idx = 0 when nearest_idx is not found with findNearestIdx
size_t target_idx{0};
StateAfterDelay state_after_delay{0.0, 0.0, 0.0};
Motion current_motion{};
Shift shift{Shift::Forward}; // shift is used only to calculate the sign of pitch compensation
double stop_dist{0.0}; // signed distance that is positive when car is before the stopline
Expand Down Expand Up @@ -179,7 +191,8 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
double m_min_jerk;

// slope compensation
bool m_use_traj_for_pitch;
bool m_enable_adaptive_trajectory;
double m_adaptive_trajectory_velocity_th;
std::shared_ptr<LowpassFilter1d> m_lpf_pitch{nullptr};
double m_max_pitch_rad;
double m_min_pitch_rad;
Expand Down Expand Up @@ -271,11 +284,9 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro

/**
* @brief calculate control command based on the current control state
* @param [in] current_pose current ego pose
* @param [in] control_data control data
*/
Motion calcCtrlCmd(
const geometry_msgs::msg::Pose & current_pose, const ControlData & control_data);
Motion calcCtrlCmd(const ControlData & control_data);

/**
* @brief publish control command
Expand Down Expand Up @@ -304,9 +315,9 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro

/**
* @brief calculate direction (forward or backward) that vehicle moves
* @param [in] nearest_idx nearest index on trajectory to vehicle
* @param [in] control_data data for control calculation
*/
enum Shift getCurrentShift(const size_t nearest_idx) const;
enum Shift getCurrentShift(const ControlData & control_data) const;

/**
* @brief filter acceleration command with limitation of acceleration and jerk, and slope
Expand Down Expand Up @@ -336,16 +347,16 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
* @param [in] motion delay compensated target motion
*/
Motion keepBrakeBeforeStop(
const autoware_auto_planning_msgs::msg::Trajectory & traj, const Motion & target_motion,
const size_t nearest_idx) const;
const ControlData & control_data, const Motion & target_motion, const size_t nearest_idx) const;

/**
* @brief interpolate trajectory point that is nearest to vehicle
* @param [in] traj reference trajectory
* @param [in] point vehicle position
* @param [in] nearest_idx index of the trajectory point nearest to the vehicle position
*/
autoware_auto_planning_msgs::msg::TrajectoryPoint calcInterpolatedTargetValue(
std::pair<autoware_auto_planning_msgs::msg::TrajectoryPoint, size_t>
calcInterpolatedTrajPointAndSegment(
const autoware_auto_planning_msgs::msg::Trajectory & traj,
const geometry_msgs::msg::Pose & pose) const;

Expand All @@ -354,18 +365,14 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
* @param [in] current_motion current velocity and acceleration of the vehicle
* @param [in] delay_compensation_time predicted time delay
*/
double predictedVelocityInTargetPoint(
StateAfterDelay predictedStateAfterDelay(
const Motion current_motion, const double delay_compensation_time) const;

/**
* @brief calculate velocity feedback with feed forward and pid controller
* @param [in] target_motion reference velocity and acceleration. This acceleration will be used
* as feed forward.
* @param [in] dt time step to use
* @param [in] current_vel current velocity of the vehicle
* @param [in] control_data data for control calculation
*/
double applyVelocityFeedback(
const Motion target_motion, const double dt, const double current_vel, const Shift & shift);
double applyVelocityFeedback(const ControlData & control_data);

/**
* @brief update variables for debugging about pitch
Expand All @@ -378,12 +385,9 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
/**
* @brief update variables for velocity and acceleration
* @param [in] ctrl_cmd latest calculated control command
* @param [in] current_pose current pose of the vehicle
* @param [in] control_data data for control calculation
*/
void updateDebugVelAcc(
const Motion & ctrl_cmd, const geometry_msgs::msg::Pose & current_pose,
const ControlData & control_data);
void updateDebugVelAcc(const ControlData & control_data);
};
} // namespace autoware::motion::control::pid_longitudinal_controller

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,19 +5,19 @@
enable_smooth_stop: true
enable_overshoot_emergency: true
enable_large_tracking_error_emergency: true
enable_slope_compensation: false
enable_slope_compensation: true
enable_keep_stopped_until_steer_convergence: true

# state transition
drive_state_stop_dist: 0.5
drive_state_offset_stop_dist: 1.0
stopping_state_stop_dist: 0.49
stopping_state_stop_dist: 0.5
stopped_state_entry_duration_time: 0.1
stopped_state_entry_vel: 0.1
stopped_state_entry_vel: 0.01
stopped_state_entry_acc: 0.1
emergency_state_overshoot_stop_dist: 1.5
emergency_state_traj_trans_dev: 3.0
emergency_state_traj_rot_dev: 0.7
emergency_state_traj_rot_dev: 0.7854

# drive state
kp: 1.0
Expand All @@ -38,7 +38,7 @@

# smooth stop state
smooth_stop_max_strong_acc: -0.5
smooth_stop_min_strong_acc: -1.0
smooth_stop_min_strong_acc: -0.8
smooth_stop_weak_acc: -0.3
smooth_stop_weak_stop_acc: -0.8
smooth_stop_strong_stop_acc: -3.4
Expand Down Expand Up @@ -67,8 +67,9 @@
max_jerk: 2.0
min_jerk: -5.0

# pitch
use_trajectory_for_pitch_calculation: false
# slope compensation
lpf_pitch_gain: 0.95
enable_adaptive_trajectory: true
adaptive_trajectory_velocity_th: 1.0
max_pitch_rad: 0.1
min_pitch_rad: -0.1
Original file line number Diff line number Diff line change
Expand Up @@ -84,25 +84,25 @@ double getPitchByPose(const Quaternion & quaternion_msg)
}

double getPitchByTraj(
const Trajectory & trajectory, const size_t nearest_idx, const double wheel_base)
const Trajectory & trajectory, const size_t start_idx, const double wheel_base)
{
// cannot calculate pitch
if (trajectory.points.size() <= 1) {
return 0.0;
}

const auto [prev_idx, next_idx] = [&]() {
for (size_t i = nearest_idx + 1; i < trajectory.points.size(); ++i) {
for (size_t i = start_idx + 1; i < trajectory.points.size(); ++i) {
const double dist = tier4_autoware_utils::calcDistance2d(
trajectory.points.at(nearest_idx), trajectory.points.at(i));
trajectory.points.at(start_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);
return std::make_pair(start_idx, i);
}
}
// 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);
std::min(start_idx, trajectory.points.size() - 2), trajectory.points.size() - 1);
}();

return tier4_autoware_utils::calcElevationAngle(
Expand Down Expand Up @@ -168,5 +168,33 @@ double applyDiffLimitFilter(
const double min_val = -max_val;
return applyDiffLimitFilter(input_val, prev_val, dt, max_val, min_val);
}

geometry_msgs::msg::Pose findTrajectoryPoseAfterDistance(
const size_t src_idx, const double distance,
const autoware_auto_planning_msgs::msg::Trajectory & trajectory)
{
double remain_dist = distance;
geometry_msgs::msg::Pose p = trajectory.points.back().pose;
for (size_t i = src_idx; i < trajectory.points.size() - 1; ++i) {
const double dist = tier4_autoware_utils::calcDistance3d(
trajectory.points.at(i).pose, trajectory.points.at(i + 1).pose);
if (remain_dist < dist) {
if (remain_dist <= 0.0) {
return trajectory.points.at(i).pose;
}
double ratio = remain_dist / dist;
const auto p0 = trajectory.points.at(i).pose;
const auto p1 = trajectory.points.at(i + 1).pose;
p = trajectory.points.at(i).pose;
p.position.x = interpolation::lerp(p0.position.x, p1.position.x, ratio);
p.position.y = interpolation::lerp(p0.position.y, p1.position.y, ratio);
p.position.z = interpolation::lerp(p0.position.z, p1.position.z, ratio);
p.orientation = lerpOrientation(p0.orientation, p1.orientation, ratio);
break;
}
remain_dist -= dist;
}
return p;
}
} // namespace longitudinal_utils
} // namespace autoware::motion::control::pid_longitudinal_controller
Loading

0 comments on commit 5bcff34

Please sign in to comment.