@@ -64,13 +64,25 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
64
64
double vel{0.0 };
65
65
double acc{0.0 };
66
66
};
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
+ };
68
77
enum class Shift { Forward = 0 , Reverse };
69
78
70
79
struct ControlData
71
80
{
72
81
bool is_far_from_trajectory{false };
82
+ autoware_auto_planning_msgs::msg::Trajectory interpolated_traj{};
73
83
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 };
74
86
Motion current_motion{};
75
87
Shift shift{Shift::Forward}; // shift is used only to calculate the sign of pitch compensation
76
88
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
268
280
269
281
/* *
270
282
* @brief calculate control command based on the current control state
271
- * @param [in] current_pose current ego pose
272
283
* @param [in] control_data control data
273
284
*/
274
- Motion calcCtrlCmd (
275
- const geometry_msgs::msg::Pose & current_pose, const ControlData & control_data);
285
+ Motion calcCtrlCmd (const ControlData & control_data);
276
286
277
287
/* *
278
288
* @brief publish control command
@@ -301,9 +311,9 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
301
311
302
312
/* *
303
313
* @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
305
315
*/
306
- enum Shift getCurrentShift (const size_t nearest_idx ) const ;
316
+ enum Shift getCurrentShift (const ControlData & control_data ) const ;
307
317
308
318
/* *
309
319
* @brief filter acceleration command with limitation of acceleration and jerk, and slope
@@ -342,7 +352,8 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
342
352
* @param [in] point vehicle position
343
353
* @param [in] nearest_idx index of the trajectory point nearest to the vehicle position
344
354
*/
345
- autoware_auto_planning_msgs::msg::TrajectoryPoint calcInterpolatedTargetValue (
355
+ std::pair<autoware_auto_planning_msgs::msg::TrajectoryPoint, size_t >
356
+ calcInterpolatedTrajPointAndSegment (
346
357
const autoware_auto_planning_msgs::msg::Trajectory & traj,
347
358
const geometry_msgs::msg::Pose & pose) const ;
348
359
@@ -351,18 +362,14 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
351
362
* @param [in] current_motion current velocity and acceleration of the vehicle
352
363
* @param [in] delay_compensation_time predicted time delay
353
364
*/
354
- double predictedVelocityInTargetPoint (
365
+ StateAfterDelay predictedStateAfterDelay (
355
366
const Motion current_motion, const double delay_compensation_time) const ;
356
367
357
368
/* *
358
369
* @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
363
371
*/
364
- double applyVelocityFeedback (
365
- const Motion target_motion, const double dt, const double current_vel);
372
+ double applyVelocityFeedback (const ControlData & control_data);
366
373
367
374
/* *
368
375
* @brief update variables for debugging about pitch
@@ -375,12 +382,9 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
375
382
/* *
376
383
* @brief update variables for velocity and acceleration
377
384
* @param [in] ctrl_cmd latest calculated control command
378
- * @param [in] current_pose current pose of the vehicle
379
385
* @param [in] control_data data for control calculation
380
386
*/
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);
384
388
};
385
389
} // namespace autoware::motion::control::pid_longitudinal_controller
386
390
0 commit comments