Skip to content

Commit 2119d48

Browse files
brkay54Berkay Karamanpre-commit-ci[bot]
authored
feat(pure_pursuit): add predicted trajectory (autowarefoundation#2115)
* feat(pure_pursuit): add predicted trajectory Signed-off-by: Berkay Karaman <berkay@leodrive.ai> * ci(pre-commit): autofix * clear up Signed-off-by: Berkay Karaman <berkay@leodrive.ai> * Use operator || instead of or Signed-off-by: Berkay Karaman <berkay@leodrive.ai> * comment update Signed-off-by: Berkay Karaman <berkay@leodrive.ai> Signed-off-by: Berkay Karaman <berkay@leodrive.ai> Co-authored-by: Berkay Karaman <berkay@leodrive.ai> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent 7c9f6e2 commit 2119d48

File tree

5 files changed

+269
-36
lines changed

5 files changed

+269
-36
lines changed

control/pure_pursuit/include/pure_pursuit/pure_pursuit_lateral_controller.hpp

+48-5
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright 2020 Tier IV, Inc.
1+
// Copyright 2020-2022 Tier IV, Inc., Leo Drive Teknoloji A.Ş.
22
//
33
// Licensed under the Apache License, Version 2.0 (the "License");
44
// you may not use this file except in compliance with the License.
@@ -38,6 +38,10 @@
3838
#include "tier4_autoware_utils/ros/self_pose_listener.hpp"
3939
#include "trajectory_follower/lateral_controller_base.hpp"
4040

41+
#include <motion_utils/resample/resample.hpp>
42+
#include <motion_utils/trajectory/tmp_conversion.hpp>
43+
#include <motion_utils/trajectory/trajectory.hpp>
44+
4145
#include "autoware_auto_control_msgs/msg/ackermann_lateral_command.hpp"
4246
#include "autoware_auto_planning_msgs/msg/trajectory.hpp"
4347
#include "geometry_msgs/msg/pose_stamped.hpp"
@@ -53,9 +57,18 @@ using autoware::motion::control::trajectory_follower::InputData;
5357
using autoware::motion::control::trajectory_follower::LateralControllerBase;
5458
using autoware::motion::control::trajectory_follower::LateralOutput;
5559
using autoware_auto_control_msgs::msg::AckermannLateralCommand;
60+
using autoware_auto_planning_msgs::msg::Trajectory;
61+
using autoware_auto_planning_msgs::msg::TrajectoryPoint;
5662

5763
namespace pure_pursuit
5864
{
65+
66+
struct PpOutput
67+
{
68+
double curvature;
69+
double velocity;
70+
};
71+
5972
struct Param
6073
{
6174
// Global Parameters
@@ -67,6 +80,9 @@ struct Param
6780
double min_lookahead_distance;
6881
double reverse_min_lookahead_distance; // min_lookahead_distance in reverse gear
6982
double converged_steer_rad_;
83+
double prediction_ds;
84+
double prediction_distance_length; // Total distance of prediction trajectory
85+
double resampling_ds;
7086
};
7187

7288
struct DebugData
@@ -82,16 +98,25 @@ class PurePursuitLateralController : public LateralControllerBase
8298
private:
8399
rclcpp::Node::SharedPtr node_;
84100
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_;
86103
autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr trajectory_;
87104
nav_msgs::msg::Odometry::ConstSharedPtr current_odometry_;
88105
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_;
89111

90112
bool isDataReady();
91113

92114
void onTrajectory(const autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr msg);
115+
93116
void onCurrentOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg);
94117

118+
void setResampledTrajectory();
119+
95120
// TF
96121
tf2_ros::Buffer tf_buffer_;
97122
tf2_ros::TransformListener tf_listener_;
@@ -106,6 +131,7 @@ class PurePursuitLateralController : public LateralControllerBase
106131
* @brief compute control command for path follow with a constant control period
107132
*/
108133
boost::optional<LateralOutput> run() override;
134+
109135
AckermannLateralCommand generateCtrlCmdMsg(const double target_curvature);
110136

111137
/**
@@ -114,13 +140,30 @@ class PurePursuitLateralController : public LateralControllerBase
114140
void setInputData(InputData const & input_data) override;
115141

116142
// Parameter
117-
Param param_;
143+
Param param_{};
118144

119145
// Algorithm
120146
std::unique_ptr<PurePursuit> pure_pursuit_;
121147

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);
124167

125168
// Debug
126169
mutable DebugData debug_data_;

control/pure_pursuit/include/pure_pursuit/util/planning_utils.hpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -50,7 +50,9 @@ namespace pure_pursuit
5050
namespace planning_utils
5151
{
5252
constexpr double ERROR = 1e-6;
53-
53+
double calcArcLengthFromWayPoint(
54+
const autoware_auto_planning_msgs::msg::Trajectory & input_path, const size_t src_idx,
55+
const size_t dst_idx);
5456
double calcCurvature(
5557
const geometry_msgs::msg::Point & target, const geometry_msgs::msg::Pose & curr_pose);
5658
double calcDistance2D(const geometry_msgs::msg::Point & p, const geometry_msgs::msg::Point & q);

control/pure_pursuit/package.xml

+6
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,7 @@
77
<maintainer email="takamasa.horibe@tier4.jp">Takamasa Horibe</maintainer>
88
<license>Apache License 2.0</license>
99

10+
<author email="berkay@leodrive.ai">Berkay Karaman</author>
1011
<author email="kenji.miyake@tier4.jp">Kenji Miyake</author>
1112
<author email="takamasa.horibe@tier4.jp">Takamasa Horibe</author>
1213

@@ -16,7 +17,12 @@
1617

1718
<depend>autoware_auto_control_msgs</depend>
1819
<depend>autoware_auto_planning_msgs</depend>
20+
<depend>boost</depend>
1921
<depend>geometry_msgs</depend>
22+
<depend>libboost-dev</depend>
23+
<depend>motion_common</depend>
24+
<depend>motion_utils</depend>
25+
<depend>nav_msgs</depend>
2026
<depend>rclcpp</depend>
2127
<depend>rclcpp_components</depend>
2228
<depend>sensor_msgs</depend>

0 commit comments

Comments
 (0)