Skip to content

Commit 1415c88

Browse files
committed
feat(pid_longitudinal_controller): improve delay and slope compensation
Signed-off-by: Berkay Karaman <brkay54@gmail.com>
1 parent 05f8ad2 commit 1415c88

File tree

5 files changed

+306
-182
lines changed

5 files changed

+306
-182
lines changed

control/pid_longitudinal_controller/include/pid_longitudinal_controller/longitudinal_controller_utils.hpp

+18-4
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,7 @@
2828

2929
#include <cmath>
3030
#include <limits>
31+
#include <utility>
3132

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

6970
/**
7071
* @brief calculate vehicle pose after time delay by moving the vehicle at current velocity and
@@ -88,7 +89,7 @@ Quaternion lerpOrientation(const Quaternion & o_from, const Quaternion & o_to, c
8889
* @param [in] point Interpolated point is nearest to this point.
8990
*/
9091
template <class T>
91-
TrajectoryPoint lerpTrajectoryPoint(
92+
std::pair<TrajectoryPoint, size_t> lerpTrajectoryPoint(
9293
const T & points, const Pose & pose, const double max_dist, const double max_yaw)
9394
{
9495
TrajectoryPoint interpolated_point;
@@ -107,6 +108,8 @@ TrajectoryPoint lerpTrajectoryPoint(
107108
points.at(i).pose.position.x, points.at(i + 1).pose.position.x, interpolate_ratio);
108109
interpolated_point.pose.position.y = interpolation::lerp(
109110
points.at(i).pose.position.y, points.at(i + 1).pose.position.y, interpolate_ratio);
111+
interpolated_point.pose.position.z = interpolation::lerp(
112+
points.at(i).pose.position.z, points.at(i + 1).pose.position.z, interpolate_ratio);
110113
interpolated_point.pose.orientation = lerpOrientation(
111114
points.at(i).pose.orientation, points.at(i + 1).pose.orientation, interpolate_ratio);
112115
interpolated_point.longitudinal_velocity_mps = interpolation::lerp(
@@ -120,7 +123,7 @@ TrajectoryPoint lerpTrajectoryPoint(
120123
points.at(i).heading_rate_rps, points.at(i + 1).heading_rate_rps, interpolate_ratio);
121124
}
122125

123-
return interpolated_point;
126+
return std::make_pair(interpolated_point, seg_idx);
124127
}
125128

126129
/**
@@ -144,6 +147,17 @@ double applyDiffLimitFilter(
144147
double applyDiffLimitFilter(
145148
const double input_val, const double prev_val, const double dt, const double max_val,
146149
const double min_val);
150+
151+
/**
152+
* @brief calculate the projected pose after distance from the current index
153+
* @param [in] src_idx current index
154+
* @param [in] distance distance to project
155+
* @param [in] trajectory reference trajectory
156+
*/
157+
geometry_msgs::msg::Pose findTrajectoryPoseAfterDistance(
158+
const size_t src_idx, const double distance,
159+
const autoware_auto_planning_msgs::msg::Trajectory & trajectory);
160+
147161
} // namespace longitudinal_utils
148162
} // namespace autoware::motion::control::pid_longitudinal_controller
149163

control/pid_longitudinal_controller/include/pid_longitudinal_controller/pid_longitudinal_controller.hpp

+23-21
Original file line numberDiff line numberDiff line change
@@ -65,13 +65,25 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
6565
double vel{0.0};
6666
double acc{0.0};
6767
};
68-
68+
struct StateAfterDelay
69+
{
70+
StateAfterDelay(const double velocity, const double acceleration, const double distance)
71+
: vel(velocity), acc(acceleration), running_distance(distance)
72+
{
73+
}
74+
double vel{0.0};
75+
double acc{0.0};
76+
double running_distance{0.0};
77+
};
6978
enum class Shift { Forward = 0, Reverse };
7079

7180
struct ControlData
7281
{
7382
bool is_far_from_trajectory{false};
83+
autoware_auto_planning_msgs::msg::Trajectory interpolated_traj{};
7484
size_t nearest_idx{0}; // nearest_idx = 0 when nearest_idx is not found with findNearestIdx
85+
size_t target_idx{0};
86+
StateAfterDelay state_after_delay{0.0, 0.0, 0.0};
7587
Motion current_motion{};
7688
Shift shift{Shift::Forward}; // shift is used only to calculate the sign of pitch compensation
7789
double stop_dist{0.0}; // signed distance that is positive when car is before the stopline
@@ -179,7 +191,6 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
179191
double m_min_jerk;
180192

181193
// slope compensation
182-
bool m_use_traj_for_pitch;
183194
std::shared_ptr<LowpassFilter1d> m_lpf_pitch{nullptr};
184195
double m_max_pitch_rad;
185196
double m_min_pitch_rad;
@@ -271,11 +282,9 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
271282

272283
/**
273284
* @brief calculate control command based on the current control state
274-
* @param [in] current_pose current ego pose
275285
* @param [in] control_data control data
276286
*/
277-
Motion calcCtrlCmd(
278-
const geometry_msgs::msg::Pose & current_pose, const ControlData & control_data);
287+
Motion calcCtrlCmd(const ControlData & control_data);
279288

280289
/**
281290
* @brief publish control command
@@ -304,9 +313,9 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
304313

305314
/**
306315
* @brief calculate direction (forward or backward) that vehicle moves
307-
* @param [in] nearest_idx nearest index on trajectory to vehicle
316+
* @param [in] control_data data for control calculation
308317
*/
309-
enum Shift getCurrentShift(const size_t nearest_idx) const;
318+
enum Shift getCurrentShift(const ControlData & control_data) const;
310319

311320
/**
312321
* @brief filter acceleration command with limitation of acceleration and jerk, and slope
@@ -336,16 +345,16 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
336345
* @param [in] motion delay compensated target motion
337346
*/
338347
Motion keepBrakeBeforeStop(
339-
const autoware_auto_planning_msgs::msg::Trajectory & traj, const Motion & target_motion,
340-
const size_t nearest_idx) const;
348+
const ControlData & control_data, const Motion & target_motion, const size_t nearest_idx) const;
341349

342350
/**
343351
* @brief interpolate trajectory point that is nearest to vehicle
344352
* @param [in] traj reference trajectory
345353
* @param [in] point vehicle position
346354
* @param [in] nearest_idx index of the trajectory point nearest to the vehicle position
347355
*/
348-
autoware_auto_planning_msgs::msg::TrajectoryPoint calcInterpolatedTargetValue(
356+
std::pair<autoware_auto_planning_msgs::msg::TrajectoryPoint, size_t>
357+
calcInterpolatedTrajPointAndSegment(
349358
const autoware_auto_planning_msgs::msg::Trajectory & traj,
350359
const geometry_msgs::msg::Pose & pose) const;
351360

@@ -354,18 +363,14 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
354363
* @param [in] current_motion current velocity and acceleration of the vehicle
355364
* @param [in] delay_compensation_time predicted time delay
356365
*/
357-
double predictedVelocityInTargetPoint(
366+
StateAfterDelay predictedStateAfterDelay(
358367
const Motion current_motion, const double delay_compensation_time) const;
359368

360369
/**
361370
* @brief calculate velocity feedback with feed forward and pid controller
362-
* @param [in] target_motion reference velocity and acceleration. This acceleration will be used
363-
* as feed forward.
364-
* @param [in] dt time step to use
365-
* @param [in] current_vel current velocity of the vehicle
371+
* @param [in] control_data data for control calculation
366372
*/
367-
double applyVelocityFeedback(
368-
const Motion target_motion, const double dt, const double current_vel, const Shift & shift);
373+
double applyVelocityFeedback(const ControlData & control_data);
369374

370375
/**
371376
* @brief update variables for debugging about pitch
@@ -378,12 +383,9 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
378383
/**
379384
* @brief update variables for velocity and acceleration
380385
* @param [in] ctrl_cmd latest calculated control command
381-
* @param [in] current_pose current pose of the vehicle
382386
* @param [in] control_data data for control calculation
383387
*/
384-
void updateDebugVelAcc(
385-
const Motion & ctrl_cmd, const geometry_msgs::msg::Pose & current_pose,
386-
const ControlData & control_data);
388+
void updateDebugVelAcc(const ControlData & control_data);
387389
};
388390
} // namespace autoware::motion::control::pid_longitudinal_controller
389391

control/pid_longitudinal_controller/src/longitudinal_controller_utils.cpp

+39-5
Original file line numberDiff line numberDiff line change
@@ -84,25 +84,25 @@ double getPitchByPose(const Quaternion & quaternion_msg)
8484
}
8585

8686
double getPitchByTraj(
87-
const Trajectory & trajectory, const size_t nearest_idx, const double wheel_base)
87+
const Trajectory & trajectory, const size_t start_idx, const double wheel_base)
8888
{
8989
// cannot calculate pitch
9090
if (trajectory.points.size() <= 1) {
9191
return 0.0;
9292
}
9393

9494
const auto [prev_idx, next_idx] = [&]() {
95-
for (size_t i = nearest_idx + 1; i < trajectory.points.size(); ++i) {
95+
for (size_t i = start_idx + 1; i < trajectory.points.size(); ++i) {
9696
const double dist = tier4_autoware_utils::calcDistance2d(
97-
trajectory.points.at(nearest_idx), trajectory.points.at(i));
97+
trajectory.points.at(start_idx), trajectory.points.at(i));
9898
if (dist > wheel_base) {
9999
// calculate pitch from trajectory between rear wheel (nearest) and front center (i)
100-
return std::make_pair(nearest_idx, i);
100+
return std::make_pair(start_idx, i);
101101
}
102102
}
103103
// NOTE: The ego pose is close to the goal.
104104
return std::make_pair(
105-
std::min(nearest_idx, trajectory.points.size() - 2), trajectory.points.size() - 1);
105+
std::min(start_idx, trajectory.points.size() - 2), trajectory.points.size() - 1);
106106
}();
107107

108108
return tier4_autoware_utils::calcElevationAngle(
@@ -168,5 +168,39 @@ double applyDiffLimitFilter(
168168
const double min_val = -max_val;
169169
return applyDiffLimitFilter(input_val, prev_val, dt, max_val, min_val);
170170
}
171+
172+
geometry_msgs::msg::Pose findTrajectoryPoseAfterDistance(
173+
const size_t src_idx, const double distance,
174+
const autoware_auto_planning_msgs::msg::Trajectory & trajectory)
175+
{
176+
double remain_dist = distance;
177+
geometry_msgs::msg::Pose p = trajectory.points.back().pose;
178+
for (size_t i = src_idx; i < trajectory.points.size() - 1; ++i) {
179+
const double dist = tier4_autoware_utils::calcDistance3d(
180+
trajectory.points.at(i).pose, trajectory.points.at(i + 1).pose);
181+
if (remain_dist < dist) {
182+
if (remain_dist <= 0.0) {
183+
return trajectory.points.at(i).pose;
184+
}
185+
double ratio = remain_dist / dist;
186+
p = trajectory.points.at(i).pose;
187+
p.position.x = interpolation::lerp(
188+
trajectory.points.at(i).pose.position.x, trajectory.points.at(i + 1).pose.position.x,
189+
ratio);
190+
p.position.y = interpolation::lerp(
191+
trajectory.points.at(i).pose.position.y, trajectory.points.at(i + 1).pose.position.y,
192+
ratio);
193+
p.position.z = interpolation::lerp(
194+
trajectory.points.at(i).pose.position.z, trajectory.points.at(i + 1).pose.position.z,
195+
ratio);
196+
p.orientation = lerpOrientation(
197+
trajectory.points.at(i).pose.orientation, trajectory.points.at(i + 1).pose.orientation,
198+
ratio);
199+
break;
200+
}
201+
remain_dist -= dist;
202+
}
203+
return p;
204+
}
171205
} // namespace longitudinal_utils
172206
} // namespace autoware::motion::control::pid_longitudinal_controller

0 commit comments

Comments
 (0)