Skip to content

Commit 192c083

Browse files
authored
Merge pull request #1810 from tier4/tmp/beta/v0.29.0-2
feat: cherry-pick change of beta/v4.0.2
2 parents 5357377 + 287c5a2 commit 192c083

File tree

54 files changed

+7215
-2815
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

54 files changed

+7215
-2815
lines changed
File renamed without changes.

control/autoware_mpc_lateral_controller/README.md

+7
Original file line numberDiff line numberDiff line change
@@ -95,6 +95,7 @@ AutonomouStuff Lexus RX 450h for under 40 km/h driving.
9595
| use_steer_prediction | boolean | flag for using steer prediction (do not use steer measurement) | false |
9696
| admissible_position_error | double | stop vehicle when following position error is larger than this value [m] | 5.0 |
9797
| admissible_yaw_error_rad | double | stop vehicle when following yaw angle error is larger than this value [rad] | 1.57 |
98+
| use_delayed_initial_state | boolean | flag to use x0_delayed as initial state for predicted trajectory | true |
9899

99100
#### Path Smoothing
100101

@@ -202,6 +203,12 @@ Defined in the `steering_offset` namespace. This logic is designed as simple as
202203
| cf | double | front cornering power [N/rad] | 155494.663 |
203204
| cr | double | rear cornering power [N/rad] | 155494.663 |
204205

206+
#### Debug
207+
208+
| Name | Type | Description | Default value |
209+
| :------------------------- | :------ | :-------------------------------------------------------------------------------- | :------------ |
210+
| publish_debug_trajectories | boolean | publish predicted trajectory and resampled reference trajectory for debug purpose | true |
211+
205212
### How to tune MPC parameters
206213

207214
#### Set kinematics information

control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc.hpp

+10-2
Original file line numberDiff line numberDiff line change
@@ -222,6 +222,7 @@ class MPC
222222
double m_min_prediction_length = 5.0; // Minimum prediction distance.
223223

224224
rclcpp::Publisher<Trajectory>::SharedPtr m_debug_frenet_predicted_trajectory_pub;
225+
rclcpp::Publisher<Trajectory>::SharedPtr m_debug_resampled_reference_trajectory_pub;
225226
/**
226227
* @brief Get variables for MPC calculation.
227228
* @param trajectory The reference trajectory.
@@ -341,11 +342,14 @@ class MPC
341342
* @param Uex optimized input.
342343
* @param mpc_resampled_ref_traj reference trajectory resampled in the mpc time-step
343344
* @param dt delta time used in the mpc problem.
345+
* @param coordinate String specifying the coordinate system ("world" or "frenet", default is
346+
* "world")
344347
* @return predicted path
345348
*/
346349
Trajectory calculatePredictedTrajectory(
347350
const MPCMatrix & mpc_matrix, const Eigen::MatrixXd & x0, const Eigen::MatrixXd & Uex,
348-
const MPCTrajectory & mpc_resampled_ref_traj, const double dt) const;
351+
const MPCTrajectory & reference_trajectory, const double dt,
352+
const std::string & coordinate = "world") const;
349353

350354
/**
351355
* @brief Check if the MPC matrix has any invalid values.
@@ -426,7 +430,11 @@ class MPC
426430
double ego_nearest_dist_threshold = 3.0; // Threshold for nearest index search based on distance.
427431
double ego_nearest_yaw_threshold = M_PI_2; // Threshold for nearest index search based on yaw.
428432

429-
bool m_debug_publish_predicted_trajectory = false; // Flag to publish debug predicted trajectory
433+
bool m_use_delayed_initial_state =
434+
true; // Flag to use x0_delayed as initial state for predicted trajectory
435+
436+
bool m_publish_debug_trajectories = false; // Flag to publish predicted trajectory and
437+
// resampled reference trajectory for debug purpose
430438

431439
//!< Constructor.
432440
explicit MPC(rclcpp::Node & node);

control/autoware_mpc_lateral_controller/param/lateral_controller_defaults.param.yaml

+2-1
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,7 @@
55
use_steer_prediction: false # flag for using steer prediction (do not use steer measurement)
66
admissible_position_error: 5.0 # stop mpc calculation when error is larger than the following value
77
admissible_yaw_error_rad: 1.57 # stop mpc calculation when error is larger than the following value
8+
use_delayed_initial_state: true # flag to use x0_delayed as initial state for predicted trajectory
89

910
# -- path smoothing --
1011
enable_path_smoothing: false # flag for path smoothing
@@ -84,4 +85,4 @@
8485
cf: 155494.663
8586
cr: 155494.663
8687

87-
debug_publish_predicted_trajectory: false # publish debug predicted trajectory in Frenet coordinate
88+
publish_debug_trajectories: true # flag to publish predicted trajectory and resampled reference trajectory for debug purpose

control/autoware_mpc_lateral_controller/src/mpc.cpp

+34-17
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,8 @@ MPC::MPC(rclcpp::Node & node)
3333
{
3434
m_debug_frenet_predicted_trajectory_pub = node.create_publisher<Trajectory>(
3535
"~/debug/predicted_trajectory_in_frenet_coordinate", rclcpp::QoS(1));
36+
m_debug_resampled_reference_trajectory_pub =
37+
node.create_publisher<Trajectory>("~/debug/resampled_reference_trajectory", rclcpp::QoS(1));
3638
}
3739

3840
bool MPC::calculateMPC(
@@ -104,8 +106,19 @@ bool MPC::calculateMPC(
104106
m_raw_steer_cmd_prev = Uex(0);
105107

106108
/* calculate predicted trajectory */
107-
predicted_trajectory =
108-
calculatePredictedTrajectory(mpc_matrix, x0, Uex, mpc_resampled_ref_trajectory, prediction_dt);
109+
Eigen::VectorXd initial_state = m_use_delayed_initial_state ? x0_delayed : x0;
110+
predicted_trajectory = calculatePredictedTrajectory(
111+
mpc_matrix, initial_state, Uex, mpc_resampled_ref_trajectory, prediction_dt, "world");
112+
113+
// Publish predicted trajectories in different coordinates for debugging purposes
114+
if (m_publish_debug_trajectories) {
115+
// Calculate and publish predicted trajectory in Frenet coordinate
116+
auto predicted_trajectory_frenet = calculatePredictedTrajectory(
117+
mpc_matrix, initial_state, Uex, mpc_resampled_ref_trajectory, prediction_dt, "frenet");
118+
predicted_trajectory_frenet.header.stamp = m_clock->now();
119+
predicted_trajectory_frenet.header.frame_id = "map";
120+
m_debug_frenet_predicted_trajectory_pub->publish(predicted_trajectory_frenet);
121+
}
109122

110123
// prepare diagnostic message
111124
diagnostic =
@@ -310,6 +323,13 @@ std::pair<bool, MPCTrajectory> MPC::resampleMPCTrajectoryByTime(
310323
warn_throttle("calculateMPC: mpc resample error. stop mpc calculation. check code!");
311324
return {false, {}};
312325
}
326+
// Publish resampled reference trajectory for debug purpose.
327+
if (m_publish_debug_trajectories) {
328+
auto converted_output = MPCUtils::convertToAutowareTrajectory(output);
329+
converted_output.header.stamp = m_clock->now();
330+
converted_output.header.frame_id = "map";
331+
m_debug_resampled_reference_trajectory_pub->publish(converted_output);
332+
}
313333
return {true, output};
314334
}
315335

@@ -785,12 +805,21 @@ VectorXd MPC::calcSteerRateLimitOnTrajectory(
785805

786806
Trajectory MPC::calculatePredictedTrajectory(
787807
const MPCMatrix & mpc_matrix, const Eigen::MatrixXd & x0, const Eigen::MatrixXd & Uex,
788-
const MPCTrajectory & reference_trajectory, const double dt) const
808+
const MPCTrajectory & reference_trajectory, const double dt, const std::string & coordinate) const
789809
{
790-
const auto predicted_mpc_trajectory =
791-
m_vehicle_model_ptr->calculatePredictedTrajectoryInWorldCoordinate(
810+
MPCTrajectory predicted_mpc_trajectory;
811+
812+
if (coordinate == "world") {
813+
predicted_mpc_trajectory = m_vehicle_model_ptr->calculatePredictedTrajectoryInWorldCoordinate(
814+
mpc_matrix.Aex, mpc_matrix.Bex, mpc_matrix.Cex, mpc_matrix.Wex, x0, Uex, reference_trajectory,
815+
dt);
816+
} else if (coordinate == "frenet") {
817+
predicted_mpc_trajectory = m_vehicle_model_ptr->calculatePredictedTrajectoryInFrenetCoordinate(
792818
mpc_matrix.Aex, mpc_matrix.Bex, mpc_matrix.Cex, mpc_matrix.Wex, x0, Uex, reference_trajectory,
793819
dt);
820+
} else {
821+
throw std::invalid_argument("Invalid coordinate system specified. Use 'world' or 'frenet'.");
822+
}
794823

795824
// do not over the reference trajectory
796825
const auto predicted_length = MPCUtils::calcMPCTrajectoryArcLength(reference_trajectory);
@@ -799,18 +828,6 @@ Trajectory MPC::calculatePredictedTrajectory(
799828

800829
const auto predicted_trajectory = MPCUtils::convertToAutowareTrajectory(clipped_trajectory);
801830

802-
// Publish trajectory in relative coordinate for debug purpose.
803-
if (m_debug_publish_predicted_trajectory) {
804-
const auto frenet = m_vehicle_model_ptr->calculatePredictedTrajectoryInFrenetCoordinate(
805-
mpc_matrix.Aex, mpc_matrix.Bex, mpc_matrix.Cex, mpc_matrix.Wex, x0, Uex, reference_trajectory,
806-
dt);
807-
auto frenet_clipped = MPCUtils::convertToAutowareTrajectory(
808-
MPCUtils::clipTrajectoryByLength(frenet, predicted_length));
809-
frenet_clipped.header.stamp = m_clock->now();
810-
frenet_clipped.header.frame_id = "map";
811-
m_debug_frenet_predicted_trajectory_pub->publish(frenet_clipped);
812-
}
813-
814831
return predicted_trajectory;
815832
}
816833

control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -134,7 +134,9 @@ MpcLateralController::MpcLateralController(rclcpp::Node & node)
134134
m_mpc->ego_nearest_dist_threshold = m_ego_nearest_dist_threshold;
135135
m_mpc->ego_nearest_yaw_threshold = m_ego_nearest_yaw_threshold;
136136

137-
m_mpc->m_debug_publish_predicted_trajectory = dp_bool("debug_publish_predicted_trajectory");
137+
m_mpc->m_use_delayed_initial_state = dp_bool("use_delayed_initial_state");
138+
139+
m_mpc->m_publish_debug_trajectories = dp_bool("publish_debug_trajectories");
138140

139141
m_pub_predicted_traj = node.create_publisher<Trajectory>("~/output/predicted_trajectory", 1);
140142
m_pub_debug_values =

control/autoware_trajectory_follower_node/param/lateral/mpc.param.yaml

+2-1
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,7 @@
55
use_steer_prediction: false # flag for using steer prediction (do not use steer measurement)
66
admissible_position_error: 5.0 # stop mpc calculation when error is larger than the following value
77
admissible_yaw_error_rad: 1.57 # stop mpc calculation when error is larger than the following value
8+
use_delayed_initial_state: true # flag to use x0_delayed as initial state for predicted trajectory
89

910
# -- path smoothing --
1011
enable_path_smoothing: false # flag for path smoothing
@@ -75,4 +76,4 @@
7576
average_num: 1000
7677
steering_offset_limit: 0.02
7778

78-
debug_publish_predicted_trajectory: false # publish debug predicted trajectory in Frenet coordinate
79+
publish_debug_trajectories: true # flag to publish predicted trajectory and resampled reference trajectory for debug purpose

perception/multi_object_tracker/src/multi_object_tracker_core.cpp

+5
Original file line numberDiff line numberDiff line change
@@ -209,6 +209,11 @@ void MultiObjectTracker::onTrigger()
209209
const bool is_objects_ready = input_manager_->getObjects(current_time, objects_list);
210210
if (!is_objects_ready) return;
211211
onMessage(objects_list);
212+
// Publish without delay compensation
213+
if (!publish_timer_) {
214+
const auto latest_object_time = rclcpp::Time(objects_list.back().second.header.stamp);
215+
checkAndPublish(latest_object_time);
216+
}
212217
}
213218

214219
void MultiObjectTracker::onTimer()

planning/autoware_route_handler/include/autoware/route_handler/route_handler.hpp

+3
Original file line numberDiff line numberDiff line change
@@ -324,6 +324,9 @@ class RouteHandler
324324
lanelet::ConstLanelets getShoulderLaneletsAtPose(const Pose & pose) const;
325325
lanelet::ConstPolygon3d getIntersectionAreaById(const lanelet::Id id) const;
326326

327+
Pose get_pose_from_2d_arc_length(
328+
const lanelet::ConstLanelets & lanelet_sequence, const double s) const;
329+
327330
private:
328331
// MUST
329332
lanelet::routing::RoutingGraphPtr routing_graph_ptr_;

planning/autoware_route_handler/src/route_handler.cpp

+27
Original file line numberDiff line numberDiff line change
@@ -46,6 +46,8 @@ namespace autoware::route_handler
4646
{
4747
namespace
4848
{
49+
using autoware::universe_utils::createPoint;
50+
using autoware::universe_utils::createQuaternionFromYaw;
4951
using autoware_planning_msgs::msg::LaneletPrimitive;
5052
using autoware_planning_msgs::msg::Path;
5153
using geometry_msgs::msg::Pose;
@@ -2225,4 +2227,29 @@ std::optional<lanelet::routing::LaneletPath> RouteHandler::findDrivableLanePath(
22252227
if (route) return route->shortestPath();
22262228
return {};
22272229
}
2230+
2231+
Pose RouteHandler::get_pose_from_2d_arc_length(
2232+
const lanelet::ConstLanelets & lanelet_sequence, const double s) const
2233+
{
2234+
double accumulated_distance2d = 0;
2235+
for (const auto & llt : lanelet_sequence) {
2236+
const auto & centerline = llt.centerline();
2237+
for (auto it = centerline.begin(); std::next(it) != centerline.end(); ++it) {
2238+
const auto pt = *it;
2239+
const auto next_pt = *std::next(it);
2240+
const double distance2d = lanelet::geometry::distance2d(to2D(pt), to2D(next_pt));
2241+
if (accumulated_distance2d + distance2d > s) {
2242+
const double ratio = (s - accumulated_distance2d) / distance2d;
2243+
const auto interpolated_pt = pt.basicPoint() * (1 - ratio) + next_pt.basicPoint() * ratio;
2244+
const auto yaw = std::atan2(next_pt.y() - pt.y(), next_pt.x() - pt.x());
2245+
Pose pose;
2246+
pose.position = createPoint(interpolated_pt.x(), interpolated_pt.y(), interpolated_pt.z());
2247+
pose.orientation = createQuaternionFromYaw(yaw);
2248+
return pose;
2249+
}
2250+
accumulated_distance2d += distance2d;
2251+
}
2252+
}
2253+
return Pose{};
2254+
}
22282255
} // namespace autoware::route_handler

planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/interface.cpp

+3
Original file line numberDiff line numberDiff line change
@@ -44,11 +44,14 @@ AvoidanceByLaneChangeInterface::AvoidanceByLaneChangeInterface(
4444
{
4545
}
4646

47+
// cppcheck-suppress unusedFunction
4748
bool AvoidanceByLaneChangeInterface::isExecutionRequested() const
4849
{
4950
return module_type_->isLaneChangeRequired() && module_type_->specialRequiredCheck() &&
5051
module_type_->isValidPath();
5152
}
53+
54+
// cppcheck-suppress unusedFunction
5255
void AvoidanceByLaneChangeInterface::processOnEntry()
5356
{
5457
waitApproval();

planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/manager.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -187,8 +187,8 @@ void AvoidanceByLaneChangeModuleManager::init(rclcpp::Node * node)
187187
avoidance_parameters_ = std::make_shared<AvoidanceByLCParameters>(p);
188188
}
189189

190-
std::unique_ptr<SceneModuleInterface>
191-
AvoidanceByLaneChangeModuleManager::createNewSceneModuleInstance()
190+
// cppcheck-suppress unusedFunction
191+
SMIPtr AvoidanceByLaneChangeModuleManager::createNewSceneModuleInstance()
192192
{
193193
return std::make_unique<AvoidanceByLaneChangeInterface>(
194194
name_, *node_, parameters_, avoidance_parameters_, rtc_interface_ptr_map_,

planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/manager.hpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,8 @@ using autoware::behavior_path_planner::LaneChangeModuleManager;
3232
using autoware::behavior_path_planner::LaneChangeModuleType;
3333
using autoware::behavior_path_planner::SceneModuleInterface;
3434

35+
using SMIPtr = std::unique_ptr<SceneModuleInterface>;
36+
3537
class AvoidanceByLaneChangeModuleManager : public LaneChangeModuleManager
3638
{
3739
public:
@@ -44,7 +46,7 @@ class AvoidanceByLaneChangeModuleManager : public LaneChangeModuleManager
4446

4547
void init(rclcpp::Node * node) override;
4648

47-
std::unique_ptr<SceneModuleInterface> createNewSceneModuleInstance() override;
49+
SMIPtr createNewSceneModuleInstance() override;
4850

4951
private:
5052
std::shared_ptr<AvoidanceByLCParameters> avoidance_parameters_;

planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/scene.cpp

+50-13
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020
#include "autoware/behavior_path_planner_common/utils/utils.hpp"
2121
#include "autoware/behavior_path_static_obstacle_avoidance_module/utils.hpp"
2222

23+
#include <autoware/behavior_path_lane_change_module/utils/calculation.hpp>
2324
#include <autoware/behavior_path_lane_change_module/utils/utils.hpp>
2425
#include <autoware/behavior_path_static_obstacle_avoidance_module/data_structs.hpp>
2526
#include <lanelet2_extension/utility/utilities.hpp>
@@ -33,14 +34,55 @@
3334
#include <optional>
3435
#include <utility>
3536

37+
namespace
38+
{
39+
geometry_msgs::msg::Point32 create_point32(const geometry_msgs::msg::Pose & pose)
40+
{
41+
geometry_msgs::msg::Point32 p;
42+
p.x = static_cast<float>(pose.position.x);
43+
p.y = static_cast<float>(pose.position.y);
44+
p.z = static_cast<float>(pose.position.z);
45+
return p;
46+
};
47+
48+
geometry_msgs::msg::Polygon create_execution_area(
49+
const autoware::vehicle_info_utils::VehicleInfo & vehicle_info,
50+
const geometry_msgs::msg::Pose & pose, double additional_lon_offset, double additional_lat_offset)
51+
{
52+
const double & base_to_front = vehicle_info.max_longitudinal_offset_m;
53+
const double & width = vehicle_info.vehicle_width_m;
54+
const double & base_to_rear = vehicle_info.rear_overhang_m;
55+
56+
// if stationary object, extend forward and backward by the half of lon length
57+
const double forward_lon_offset = base_to_front + additional_lon_offset;
58+
const double backward_lon_offset = -base_to_rear;
59+
const double lat_offset = width / 2.0 + additional_lat_offset;
60+
61+
const auto p1 =
62+
autoware::universe_utils::calcOffsetPose(pose, forward_lon_offset, lat_offset, 0.0);
63+
const auto p2 =
64+
autoware::universe_utils::calcOffsetPose(pose, forward_lon_offset, -lat_offset, 0.0);
65+
const auto p3 =
66+
autoware::universe_utils::calcOffsetPose(pose, backward_lon_offset, -lat_offset, 0.0);
67+
const auto p4 =
68+
autoware::universe_utils::calcOffsetPose(pose, backward_lon_offset, lat_offset, 0.0);
69+
geometry_msgs::msg::Polygon polygon;
70+
71+
polygon.points.push_back(create_point32(p1));
72+
polygon.points.push_back(create_point32(p2));
73+
polygon.points.push_back(create_point32(p3));
74+
polygon.points.push_back(create_point32(p4));
75+
76+
return polygon;
77+
}
78+
} // namespace
79+
3680
namespace autoware::behavior_path_planner
3781
{
3882
using autoware::behavior_path_planner::Direction;
3983
using autoware::behavior_path_planner::LaneChangeModuleType;
4084
using autoware::behavior_path_planner::ObjectInfo;
4185
using autoware::behavior_path_planner::Point2d;
42-
using autoware::behavior_path_planner::utils::lane_change::debug::createExecutionArea;
43-
namespace utils = autoware::behavior_path_planner::utils;
4486

4587
AvoidanceByLaneChange::AvoidanceByLaneChange(
4688
const std::shared_ptr<LaneChangeParameters> & parameters,
@@ -82,9 +124,9 @@ bool AvoidanceByLaneChange::specialRequiredCheck() const
82124

83125
const auto & nearest_object = data.target_objects.front();
84126
const auto minimum_avoid_length = calcMinAvoidanceLength(nearest_object);
85-
const auto minimum_lane_change_length = calcMinimumLaneChangeLength();
127+
const auto minimum_lane_change_length = calc_minimum_dist_buffer();
86128

87-
lane_change_debug_.execution_area = createExecutionArea(
129+
lane_change_debug_.execution_area = create_execution_area(
88130
getCommonParam().vehicle_info, getEgoPose(),
89131
std::max(minimum_lane_change_length, minimum_avoid_length), calcLateralOffset());
90132

@@ -273,16 +315,11 @@ double AvoidanceByLaneChange::calcMinAvoidanceLength(const ObjectData & nearest_
273315
return avoidance_helper_->getMinAvoidanceDistance(shift_length);
274316
}
275317

276-
double AvoidanceByLaneChange::calcMinimumLaneChangeLength() const
318+
double AvoidanceByLaneChange::calc_minimum_dist_buffer() const
277319
{
278-
const auto current_lanes = get_current_lanes();
279-
if (current_lanes.empty()) {
280-
RCLCPP_DEBUG(logger_, "no empty lanes");
281-
return std::numeric_limits<double>::infinity();
282-
}
283-
284-
return utils::lane_change::calcMinimumLaneChangeLength(
285-
getRouteHandler(), current_lanes.back(), *lane_change_parameters_, direction_);
320+
const auto [_, dist_buffer] = utils::lane_change::calculation::calc_lc_length_and_dist_buffer(
321+
common_data_ptr_, get_current_lanes());
322+
return dist_buffer.min;
286323
}
287324

288325
double AvoidanceByLaneChange::calcLateralOffset() const

planning/behavior_path_planner/autoware_behavior_path_avoidance_by_lane_change_module/src/scene.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -63,7 +63,7 @@ class AvoidanceByLaneChange : public NormalLaneChange
6363
void fillAvoidanceTargetObjects(AvoidancePlanningData & data, AvoidanceDebugData & debug) const;
6464

6565
double calcMinAvoidanceLength(const ObjectData & nearest_object) const;
66-
double calcMinimumLaneChangeLength() const;
66+
double calc_minimum_dist_buffer() const;
6767
double calcLateralOffset() const;
6868
};
6969
} // namespace autoware::behavior_path_planner

0 commit comments

Comments
 (0)