Skip to content

Commit c16d911

Browse files
committed
feat(pid_longitudinal_controller): fix some bugs and improve delay compensation autowarefoundation#4712
Signed-off-by: Berkay Karaman <brkay54@gmail.com> update d not sure stopped style(pre-commit): autofix add copysign denem style(pre-commit): autofix
1 parent 66c6e15 commit c16d911

File tree

5 files changed

+449
-364
lines changed

5 files changed

+449
-364
lines changed

control/pid_longitudinal_controller/include/pid_longitudinal_controller/longitudinal_controller_utils.hpp

+16-6
Original file line numberDiff line numberDiff line change
@@ -75,9 +75,8 @@ double calcElevationAngle(const TrajectoryPoint & p_from, const TrajectoryPoint
7575
* @brief calculate vehicle pose after time delay by moving the vehicle at current velocity and
7676
* acceleration for delayed time
7777
*/
78-
Pose calcPoseAfterTimeDelay(
79-
const Pose & current_pose, const double delay_time, const double current_vel,
80-
const double current_acc);
78+
std::pair<double, double> calcDistAndVelAfterTimeDelay(
79+
const double delay_time, const double current_vel, const double current_acc);
8180

8281
/**
8382
* @brief apply linear interpolation to orientation
@@ -93,7 +92,7 @@ Quaternion lerpOrientation(const Quaternion & o_from, const Quaternion & o_to, c
9392
* @param [in] point Interpolated point is nearest to this point.
9493
*/
9594
template <class T>
96-
TrajectoryPoint lerpTrajectoryPoint(
95+
std::pair<TrajectoryPoint, size_t> lerpTrajectoryPoint(
9796
const T & points, const Pose & pose, const double max_dist, const double max_yaw)
9897
{
9998
TrajectoryPoint interpolated_point;
@@ -112,6 +111,8 @@ TrajectoryPoint lerpTrajectoryPoint(
112111
points.at(i).pose.position.x, points.at(i + 1).pose.position.x, interpolate_ratio);
113112
interpolated_point.pose.position.y = interpolation::lerp(
114113
points.at(i).pose.position.y, points.at(i + 1).pose.position.y, interpolate_ratio);
114+
interpolated_point.pose.position.z = interpolation::lerp(
115+
points.at(i).pose.position.z, points.at(i + 1).pose.position.z, interpolate_ratio);
115116
interpolated_point.pose.orientation = lerpOrientation(
116117
points.at(i).pose.orientation, points.at(i + 1).pose.orientation, interpolate_ratio);
117118
interpolated_point.longitudinal_velocity_mps = interpolation::lerp(
@@ -125,7 +126,7 @@ TrajectoryPoint lerpTrajectoryPoint(
125126
points.at(i).heading_rate_rps, points.at(i + 1).heading_rate_rps, interpolate_ratio);
126127
}
127128

128-
return interpolated_point;
129+
return std::make_pair(interpolated_point, seg_idx);
129130
}
130131

131132
/**
@@ -149,7 +150,16 @@ double applyDiffLimitFilter(
149150
double applyDiffLimitFilter(
150151
const double input_val, const double prev_val, const double dt, const double max_val,
151152
const double min_val);
153+
154+
/**
155+
* @brief calculate the projected pose after distance from the current index
156+
* @param [in] src_idx current index
157+
* @param [in] distance distance to project
158+
* @param [in] trajectory reference trajectory
159+
*/
160+
geometry_msgs::msg::Pose findTrajectoryPoseAfterDistance(
161+
const size_t src_idx, const double distance,
162+
const autoware_auto_planning_msgs::msg::Trajectory & trajectory);
152163
} // namespace longitudinal_utils
153164
} // namespace autoware::motion::control::pid_longitudinal_controller
154-
155165
#endif // PID_LONGITUDINAL_CONTROLLER__LONGITUDINAL_CONTROLLER_UTILS_HPP_

control/pid_longitudinal_controller/include/pid_longitudinal_controller/pid_longitudinal_controller.hpp

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

7079
struct ControlData
7180
{
7281
bool is_far_from_trajectory{false};
82+
autoware_auto_planning_msgs::msg::Trajectory interpolated_traj{};
7383
size_t nearest_idx{0}; // nearest_idx = 0 when nearest_idx is not found with findNearestIdx
84+
size_t target_idx{0};
85+
StateAfterDelay state_after_delay{0.0, 0.0, 0.0};
7486
Motion current_motion{};
7587
Shift shift{Shift::Forward}; // shift is used only to calculate the sign of pitch compensation
7688
double stop_dist{0.0}; // signed distance that is positive when car is before the stopline
@@ -268,11 +280,9 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
268280

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

277287
/**
278288
* @brief publish control command
@@ -301,9 +311,9 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
301311

302312
/**
303313
* @brief calculate direction (forward or backward) that vehicle moves
304-
* @param [in] nearest_idx nearest index on trajectory to vehicle
314+
* @param [in] control_data data for control calculation
305315
*/
306-
enum Shift getCurrentShift(const size_t nearest_idx) const;
316+
enum Shift getCurrentShift(const ControlData & control_data) const;
307317

308318
/**
309319
* @brief filter acceleration command with limitation of acceleration and jerk, and slope
@@ -342,7 +352,8 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
342352
* @param [in] point vehicle position
343353
* @param [in] nearest_idx index of the trajectory point nearest to the vehicle position
344354
*/
345-
autoware_auto_planning_msgs::msg::TrajectoryPoint calcInterpolatedTargetValue(
355+
std::pair<autoware_auto_planning_msgs::msg::TrajectoryPoint, size_t>
356+
calcInterpolatedTrajPointAndSegment(
346357
const autoware_auto_planning_msgs::msg::Trajectory & traj,
347358
const geometry_msgs::msg::Pose & pose) const;
348359

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

357368
/**
358369
* @brief calculate velocity feedback with feed forward and pid controller
359-
* @param [in] target_motion reference velocity and acceleration. This acceleration will be used
360-
* as feed forward.
361-
* @param [in] dt time step to use
362-
* @param [in] current_vel current velocity of the vehicle
370+
* @param [in] control_data data for control calculation
363371
*/
364-
double applyVelocityFeedback(
365-
const Motion target_motion, const double dt, const double current_vel);
372+
double applyVelocityFeedback(const ControlData & control_data);
366373

367374
/**
368375
* @brief update variables for debugging about pitch
@@ -375,12 +382,9 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
375382
/**
376383
* @brief update variables for velocity and acceleration
377384
* @param [in] ctrl_cmd latest calculated control command
378-
* @param [in] current_pose current pose of the vehicle
379385
* @param [in] control_data data for control calculation
380386
*/
381-
void updateDebugVelAcc(
382-
const Motion & ctrl_cmd, const geometry_msgs::msg::Pose & current_pose,
383-
const ControlData & control_data);
387+
void updateDebugVelAcc(const Motion & ctrl_cmd, const ControlData & control_data);
384388
};
385389
} // namespace autoware::motion::control::pid_longitudinal_controller
386390

control/pid_longitudinal_controller/src/longitudinal_controller_utils.cpp

+36-12
Original file line numberDiff line numberDiff line change
@@ -128,12 +128,11 @@ double calcElevationAngle(const TrajectoryPoint & p_from, const TrajectoryPoint
128128
return pitch;
129129
}
130130

131-
Pose calcPoseAfterTimeDelay(
132-
const Pose & current_pose, const double delay_time, const double current_vel,
133-
const double current_acc)
131+
std::pair<double, double> calcDistAndVelAfterTimeDelay(
132+
const double delay_time, const double current_vel, const double current_acc)
134133
{
135134
if (delay_time <= 0.0) {
136-
return current_pose;
135+
return std::make_pair(0.0, 0.0);
137136
}
138137

139138
// check time to stop
@@ -142,17 +141,11 @@ Pose calcPoseAfterTimeDelay(
142141
const double delay_time_calculation =
143142
time_to_stop > 0.0 && time_to_stop < delay_time ? time_to_stop : delay_time;
144143
// simple linear prediction
145-
const double yaw = tf2::getYaw(current_pose.orientation);
144+
const double vel_after_delay = current_vel + current_acc * delay_time_calculation;
146145
const double running_distance = delay_time_calculation * current_vel + 0.5 * current_acc *
147146
delay_time_calculation *
148147
delay_time_calculation;
149-
const double dx = running_distance * std::cos(yaw);
150-
const double dy = running_distance * std::sin(yaw);
151-
152-
auto pred_pose = current_pose;
153-
pred_pose.position.x += dx;
154-
pred_pose.position.y += dy;
155-
return pred_pose;
148+
return std::make_pair(running_distance, vel_after_delay);
156149
}
157150

158151
double lerp(const double v_from, const double v_to, const double ratio)
@@ -187,5 +180,36 @@ double applyDiffLimitFilter(
187180
const double min_val = -max_val;
188181
return applyDiffLimitFilter(input_val, prev_val, dt, max_val, min_val);
189182
}
183+
184+
geometry_msgs::msg::Pose findTrajectoryPoseAfterDistance(
185+
const size_t src_idx, const double distance,
186+
const autoware_auto_planning_msgs::msg::Trajectory & trajectory)
187+
{
188+
double remain_dist = distance;
189+
geometry_msgs::msg::Pose p = trajectory.points.back().pose;
190+
for (size_t i = src_idx; i < trajectory.points.size() - 1; ++i) {
191+
const double dist = tier4_autoware_utils::calcDistance3d(
192+
trajectory.points.at(i).pose, trajectory.points.at(i + 1).pose);
193+
if (remain_dist < dist) {
194+
if (remain_dist <= 0.0) {
195+
return trajectory.points.at(i).pose;
196+
}
197+
double ratio = remain_dist / dist;
198+
p = trajectory.points.at(i).pose;
199+
p.position.x = trajectory.points.at(i).pose.position.x +
200+
ratio * (trajectory.points.at(i + 1).pose.position.x -
201+
trajectory.points.at(i).pose.position.x);
202+
p.position.y = trajectory.points.at(i).pose.position.y +
203+
ratio * (trajectory.points.at(i + 1).pose.position.y -
204+
trajectory.points.at(i).pose.position.y);
205+
p.position.z = trajectory.points.at(i).pose.position.z +
206+
ratio * (trajectory.points.at(i + 1).pose.position.z -
207+
trajectory.points.at(i).pose.position.z);
208+
break;
209+
}
210+
remain_dist -= dist;
211+
}
212+
return p;
213+
}
190214
} // namespace longitudinal_utils
191215
} // namespace autoware::motion::control::pid_longitudinal_controller

0 commit comments

Comments
 (0)