@@ -65,13 +65,25 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
65
65
double vel{0.0 };
66
66
double acc{0.0 };
67
67
};
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
+ };
69
78
enum class Shift { Forward = 0 , Reverse };
70
79
71
80
struct ControlData
72
81
{
73
82
bool is_far_from_trajectory{false };
83
+ autoware_auto_planning_msgs::msg::Trajectory interpolated_traj{};
74
84
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 };
75
87
Motion current_motion{};
76
88
Shift shift{Shift::Forward}; // shift is used only to calculate the sign of pitch compensation
77
89
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
179
191
double m_min_jerk;
180
192
181
193
// slope compensation
182
- bool m_use_traj_for_pitch;
183
194
std::shared_ptr<LowpassFilter1d> m_lpf_pitch{nullptr };
184
195
double m_max_pitch_rad;
185
196
double m_min_pitch_rad;
@@ -271,11 +282,9 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
271
282
272
283
/* *
273
284
* @brief calculate control command based on the current control state
274
- * @param [in] current_pose current ego pose
275
285
* @param [in] control_data control data
276
286
*/
277
- Motion calcCtrlCmd (
278
- const geometry_msgs::msg::Pose & current_pose, const ControlData & control_data);
287
+ Motion calcCtrlCmd (const ControlData & control_data);
279
288
280
289
/* *
281
290
* @brief publish control command
@@ -304,9 +313,9 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
304
313
305
314
/* *
306
315
* @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
308
317
*/
309
- enum Shift getCurrentShift (const size_t nearest_idx ) const ;
318
+ enum Shift getCurrentShift (const ControlData & control_data ) const ;
310
319
311
320
/* *
312
321
* @brief filter acceleration command with limitation of acceleration and jerk, and slope
@@ -336,16 +345,16 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
336
345
* @param [in] motion delay compensated target motion
337
346
*/
338
347
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 ;
341
349
342
350
/* *
343
351
* @brief interpolate trajectory point that is nearest to vehicle
344
352
* @param [in] traj reference trajectory
345
353
* @param [in] point vehicle position
346
354
* @param [in] nearest_idx index of the trajectory point nearest to the vehicle position
347
355
*/
348
- autoware_auto_planning_msgs::msg::TrajectoryPoint calcInterpolatedTargetValue (
356
+ std::pair<autoware_auto_planning_msgs::msg::TrajectoryPoint, size_t >
357
+ calcInterpolatedTrajPointAndSegment (
349
358
const autoware_auto_planning_msgs::msg::Trajectory & traj,
350
359
const geometry_msgs::msg::Pose & pose) const ;
351
360
@@ -354,18 +363,14 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
354
363
* @param [in] current_motion current velocity and acceleration of the vehicle
355
364
* @param [in] delay_compensation_time predicted time delay
356
365
*/
357
- double predictedVelocityInTargetPoint (
366
+ StateAfterDelay predictedStateAfterDelay (
358
367
const Motion current_motion, const double delay_compensation_time) const ;
359
368
360
369
/* *
361
370
* @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
366
372
*/
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);
369
374
370
375
/* *
371
376
* @brief update variables for debugging about pitch
@@ -378,12 +383,9 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
378
383
/* *
379
384
* @brief update variables for velocity and acceleration
380
385
* @param [in] ctrl_cmd latest calculated control command
381
- * @param [in] current_pose current pose of the vehicle
382
386
* @param [in] control_data data for control calculation
383
387
*/
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);
387
389
};
388
390
} // namespace autoware::motion::control::pid_longitudinal_controller
389
391
0 commit comments