1
- // Copyright 2020 Tier IV, Inc.
1
+ // Copyright 2020-2022 Tier IV, Inc., Leo Drive Teknoloji A.Ş .
2
2
//
3
3
// Licensed under the Apache License, Version 2.0 (the "License");
4
4
// you may not use this file except in compliance with the License.
38
38
#include " tier4_autoware_utils/ros/self_pose_listener.hpp"
39
39
#include " trajectory_follower/lateral_controller_base.hpp"
40
40
41
+ #include < motion_utils/resample/resample.hpp>
42
+ #include < motion_utils/trajectory/tmp_conversion.hpp>
43
+ #include < motion_utils/trajectory/trajectory.hpp>
44
+
41
45
#include " autoware_auto_control_msgs/msg/ackermann_lateral_command.hpp"
42
46
#include " autoware_auto_planning_msgs/msg/trajectory.hpp"
43
47
#include " geometry_msgs/msg/pose_stamped.hpp"
@@ -53,9 +57,18 @@ using autoware::motion::control::trajectory_follower::InputData;
53
57
using autoware::motion::control::trajectory_follower::LateralControllerBase;
54
58
using autoware::motion::control::trajectory_follower::LateralOutput;
55
59
using autoware_auto_control_msgs::msg::AckermannLateralCommand;
60
+ using autoware_auto_planning_msgs::msg::Trajectory;
61
+ using autoware_auto_planning_msgs::msg::TrajectoryPoint;
56
62
57
63
namespace pure_pursuit
58
64
{
65
+
66
+ struct PpOutput
67
+ {
68
+ double curvature;
69
+ double velocity;
70
+ };
71
+
59
72
struct Param
60
73
{
61
74
// Global Parameters
@@ -67,6 +80,9 @@ struct Param
67
80
double min_lookahead_distance;
68
81
double reverse_min_lookahead_distance; // min_lookahead_distance in reverse gear
69
82
double converged_steer_rad_;
83
+ double prediction_ds;
84
+ double prediction_distance_length; // Total distance of prediction trajectory
85
+ double resampling_ds;
70
86
};
71
87
72
88
struct DebugData
@@ -82,16 +98,25 @@ class PurePursuitLateralController : public LateralControllerBase
82
98
private:
83
99
rclcpp::Node::SharedPtr node_;
84
100
tier4_autoware_utils::SelfPoseListener self_pose_listener_;
85
-
101
+ boost::optional<std::vector<TrajectoryPoint>> output_tp_array_;
102
+ autoware_auto_planning_msgs::msg::Trajectory::SharedPtr trajectory_resampled_;
86
103
autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr trajectory_;
87
104
nav_msgs::msg::Odometry::ConstSharedPtr current_odometry_;
88
105
autoware_auto_vehicle_msgs::msg::SteeringReport::ConstSharedPtr current_steering_;
106
+ boost::optional<AckermannLateralCommand> prev_cmd_;
107
+
108
+ // Predicted Trajectory publish
109
+ rclcpp::Publisher<autoware_auto_planning_msgs::msg::Trajectory>::SharedPtr
110
+ pub_predicted_trajectory_;
89
111
90
112
bool isDataReady ();
91
113
92
114
void onTrajectory (const autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr msg);
115
+
93
116
void onCurrentOdometry (const nav_msgs::msg::Odometry::ConstSharedPtr msg);
94
117
118
+ void setResampledTrajectory ();
119
+
95
120
// TF
96
121
tf2_ros::Buffer tf_buffer_;
97
122
tf2_ros::TransformListener tf_listener_;
@@ -106,6 +131,7 @@ class PurePursuitLateralController : public LateralControllerBase
106
131
* @brief compute control command for path follow with a constant control period
107
132
*/
108
133
boost::optional<LateralOutput> run () override ;
134
+
109
135
AckermannLateralCommand generateCtrlCmdMsg (const double target_curvature);
110
136
111
137
/* *
@@ -114,13 +140,30 @@ class PurePursuitLateralController : public LateralControllerBase
114
140
void setInputData (InputData const & input_data) override ;
115
141
116
142
// Parameter
117
- Param param_;
143
+ Param param_{} ;
118
144
119
145
// Algorithm
120
146
std::unique_ptr<PurePursuit> pure_pursuit_;
121
147
122
- boost::optional<double > calcTargetCurvature ();
123
- boost::optional<autoware_auto_planning_msgs::msg::TrajectoryPoint> calcTargetPoint () const ;
148
+ boost::optional<PpOutput> calcTargetCurvature (
149
+ bool is_control_output, geometry_msgs::msg::Pose pose);
150
+
151
+ boost::optional<autoware_auto_planning_msgs::msg::TrajectoryPoint> calcTargetPoint (
152
+ geometry_msgs::msg::Pose pose) const ;
153
+
154
+ /* *
155
+ * @brief It takes current pose, control command, and delta distance. Then it calculates next pose
156
+ * of vehicle.
157
+ */
158
+
159
+ TrajectoryPoint calcNextPose (
160
+ const double ds, TrajectoryPoint & point, AckermannLateralCommand cmd) const ;
161
+
162
+ boost::optional<Trajectory> generatePredictedTrajectory ();
163
+
164
+ boost::optional<AckermannLateralCommand> generateOutputControlCmd ();
165
+
166
+ bool calcIsSteerConverged (const AckermannLateralCommand & cmd);
124
167
125
168
// Debug
126
169
mutable DebugData debug_data_;
0 commit comments