Skip to content

Commit fcf77b0

Browse files
authored
Merge branch 'main' into traffic-light-classifier
2 parents 60178c6 + f4ea429 commit fcf77b0

File tree

41 files changed

+2346
-2011
lines changed

Some content is hidden

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

41 files changed

+2346
-2011
lines changed

common/component_interface_utils/include/component_interface_utils/rclcpp/interface.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -52,7 +52,7 @@ struct NodeInterface
5252
{ServiceLog::CLIENT_RESPONSE, "client exit"},
5353
{ServiceLog::ERROR_UNREADY, "client unready"},
5454
{ServiceLog::ERROR_TIMEOUT, "client timeout"}});
55-
RCLCPP_INFO_STREAM(node->get_logger(), type_text.at(type) << ": " << name);
55+
RCLCPP_DEBUG_STREAM(node->get_logger(), type_text.at(type) << ": " << name);
5656

5757
ServiceLog msg;
5858
msg.stamp = node->now();

common/motion_utils/include/motion_utils/trajectory/conversion.hpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717

1818
#include "autoware_auto_planning_msgs/msg/detail/trajectory__struct.hpp"
1919
#include "autoware_auto_planning_msgs/msg/detail/trajectory_point__struct.hpp"
20+
#include "std_msgs/msg/header.hpp"
2021

2122
#include <vector>
2223

@@ -34,7 +35,8 @@ namespace motion_utils
3435
* points larger than the capacity. (Tier IV)
3536
*/
3637
autoware_auto_planning_msgs::msg::Trajectory convertToTrajectory(
37-
const std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint> & trajectory);
38+
const std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint> & trajectory,
39+
const std_msgs::msg::Header & header = std_msgs::msg::Header{});
3840

3941
/**
4042
* @brief Convert autoware_auto_planning_msgs::msg::Trajectory to

common/motion_utils/src/resample/resample.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -486,7 +486,7 @@ autoware_auto_planning_msgs::msg::Path resamplePath(
486486
autoware_auto_planning_msgs::msg::Path resampled_path;
487487
resampled_path.header = input_path.header;
488488
resampled_path.left_bound = input_path.left_bound;
489-
resampled_path.right_bound = resampled_path.right_bound;
489+
resampled_path.right_bound = input_path.right_bound;
490490
resampled_path.points.resize(interpolated_pose.size());
491491
for (size_t i = 0; i < resampled_path.points.size(); ++i) {
492492
autoware_auto_planning_msgs::msg::PathPoint path_point;

common/motion_utils/src/trajectory/conversion.cpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -30,9 +30,11 @@ namespace motion_utils
3030
* points larger than the capacity. (Tier IV)
3131
*/
3232
autoware_auto_planning_msgs::msg::Trajectory convertToTrajectory(
33-
const std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint> & trajectory)
33+
const std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint> & trajectory,
34+
const std_msgs::msg::Header & header)
3435
{
3536
autoware_auto_planning_msgs::msg::Trajectory output{};
37+
output.header = header;
3638
for (const auto & pt : trajectory) output.points.push_back(pt);
3739
return output;
3840
}

common/tier4_api_utils/include/tier4_api_utils/rclcpp/client.hpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -41,20 +41,20 @@ class Client
4141
const typename ServiceT::Request::SharedPtr & request,
4242
const std::chrono::nanoseconds & timeout = std::chrono::seconds(2))
4343
{
44-
RCLCPP_INFO(logger_, "client request");
44+
RCLCPP_DEBUG(logger_, "client request");
4545

4646
if (!client_->service_is_ready()) {
47-
RCLCPP_INFO(logger_, "client available");
47+
RCLCPP_DEBUG(logger_, "client available");
4848
return {response_error("Internal service is not available."), nullptr};
4949
}
5050

5151
auto future = client_->async_send_request(request);
5252
if (future.wait_for(timeout) != std::future_status::ready) {
53-
RCLCPP_INFO(logger_, "client timeout");
53+
RCLCPP_DEBUG(logger_, "client timeout");
5454
return {response_error("Internal service has timed out."), nullptr};
5555
}
5656

57-
RCLCPP_INFO(logger_, "client response");
57+
RCLCPP_DEBUG(logger_, "client response");
5858
return {response_success(), future.get()};
5959
}
6060

common/tier4_control_rviz_plugin/src/tools/manual_controller.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -263,9 +263,9 @@ void ManualController::onClickEnableButton()
263263
{
264264
auto req = std::make_shared<EngageSrv::Request>();
265265
req->engage = true;
266-
RCLCPP_INFO(raw_node_->get_logger(), "client request");
266+
RCLCPP_DEBUG(raw_node_->get_logger(), "client request");
267267
if (!client_engage_->service_is_ready()) {
268-
RCLCPP_INFO(raw_node_->get_logger(), "client is unavailable");
268+
RCLCPP_DEBUG(raw_node_->get_logger(), "client is unavailable");
269269
return;
270270
}
271271
client_engage_->async_send_request(

common/tier4_state_rviz_plugin/src/autoware_state_panel.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -171,15 +171,15 @@ public Q_SLOTS: // NOLINT for Qt
171171
{
172172
auto req = std::make_shared<typename T::Request>();
173173

174-
RCLCPP_INFO(raw_node_->get_logger(), "client request");
174+
RCLCPP_DEBUG(raw_node_->get_logger(), "client request");
175175

176176
if (!client->service_is_ready()) {
177-
RCLCPP_INFO(raw_node_->get_logger(), "client is unavailable");
177+
RCLCPP_DEBUG(raw_node_->get_logger(), "client is unavailable");
178178
return;
179179
}
180180

181181
client->async_send_request(req, [this](typename rclcpp::Client<T>::SharedFuture result) {
182-
RCLCPP_INFO(
182+
RCLCPP_DEBUG(
183183
raw_node_->get_logger(), "Status: %d, %s", result.get()->status.code,
184184
result.get()->status.message.c_str());
185185
});

map/map_height_fitter/src/map_height_fitter.cpp

+5-5
Original file line numberDiff line numberDiff line change
@@ -101,19 +101,19 @@ bool MapHeightFitter::Impl::get_partial_point_cloud_map(const Point & point)
101101
req->area.center_y = point.y;
102102
req->area.radius = 50;
103103

104-
RCLCPP_INFO(logger, "Send request to map_loader");
104+
RCLCPP_DEBUG(logger, "Send request to map_loader");
105105
auto future = cli_map_->async_send_request(req);
106106
auto status = future.wait_for(std::chrono::seconds(1));
107107
while (status != std::future_status::ready) {
108-
RCLCPP_INFO(logger, "waiting response");
108+
RCLCPP_DEBUG(logger, "waiting response");
109109
if (!rclcpp::ok()) {
110110
return false;
111111
}
112112
status = future.wait_for(std::chrono::seconds(1));
113113
}
114114

115115
const auto res = future.get();
116-
RCLCPP_INFO(
116+
RCLCPP_DEBUG(
117117
logger, "Loaded partial pcd map from map_loader (grid size: %lu)",
118118
res->new_pointcloud_with_ids.size());
119119

@@ -168,7 +168,7 @@ std::optional<Point> MapHeightFitter::Impl::fit(const Point & position, const st
168168
const auto logger = node_->get_logger();
169169
tf2::Vector3 point(position.x, position.y, position.z);
170170

171-
RCLCPP_INFO(logger, "original point: %.3f %.3f %.3f", point.getX(), point.getY(), point.getZ());
171+
RCLCPP_DEBUG(logger, "original point: %.3f %.3f %.3f", point.getX(), point.getY(), point.getZ());
172172

173173
if (cli_map_) {
174174
if (!get_partial_point_cloud_map(position)) {
@@ -193,7 +193,7 @@ std::optional<Point> MapHeightFitter::Impl::fit(const Point & position, const st
193193
return std::nullopt;
194194
}
195195

196-
RCLCPP_INFO(logger, "modified point: %.3f %.3f %.3f", point.getX(), point.getY(), point.getZ());
196+
RCLCPP_DEBUG(logger, "modified point: %.3f %.3f %.3f", point.getX(), point.getY(), point.getZ());
197197

198198
Point result;
199199
result.x = point.getX();

planning/behavior_path_planner/config/dynamic_avoidance/dynamic_avoidance.param.yaml

+4
Original file line numberDiff line numberDiff line change
@@ -59,6 +59,10 @@
5959
max_time_for_object_lat_shift: 0.0 # [s]
6060
lpf_gain_for_lat_avoid_to_offset: 0.9 # [-]
6161

62+
max_ego_lat_acc: 0.3 # [m/ss]
63+
max_ego_lat_jerk: 0.3 # [m/sss]
64+
delay_time_ego_shift: 1.0 # [s]
65+
6266
# for same directional object
6367
overtaking_object:
6468
max_time_to_collision: 40.0 # [s]

planning/behavior_path_planner/include/behavior_path_planner/scene_module/dynamic_avoidance/dynamic_avoidance_module.hpp

+69-34
Original file line numberDiff line numberDiff line change
@@ -35,6 +35,25 @@
3535
#include <utility>
3636
#include <vector>
3737

38+
namespace
39+
{
40+
template <typename T>
41+
bool isInVector(const T & val, const std::vector<T> & vec)
42+
{
43+
return std::find(vec.begin(), vec.end(), val) != vec.end();
44+
}
45+
46+
template <typename T, typename S>
47+
std::vector<T> getAllKeys(const std::unordered_map<T, S> & map)
48+
{
49+
std::vector<T> keys;
50+
for (const auto & pair : map) {
51+
keys.push_back(pair.first);
52+
}
53+
return keys;
54+
}
55+
} // namespace
56+
3857
namespace behavior_path_planner
3958
{
4059
using autoware_auto_perception_msgs::msg::PredictedPath;
@@ -97,6 +116,10 @@ struct DynamicAvoidanceParameters
97116
double max_time_for_lat_shift{0.0};
98117
double lpf_gain_for_lat_avoid_to_offset{0.0};
99118

119+
double max_ego_lat_acc{0.0};
120+
double max_ego_lat_jerk{0.0};
121+
double delay_time_ego_shift{0.0};
122+
100123
double max_time_to_collision_overtaking_object{0.0};
101124
double start_duration_to_avoid_overtaking_object{0.0};
102125
double end_duration_to_avoid_overtaking_object{0.0};
@@ -113,6 +136,11 @@ struct TimeWhileCollision
113136
double time_to_end_collision;
114137
};
115138

139+
struct LatFeasiblePaths
140+
{
141+
std::vector<geometry_msgs::msg::Point> left_path;
142+
std::vector<geometry_msgs::msg::Point> right_path;
143+
};
116144
class DynamicAvoidanceModule : public SceneModuleInterface
117145
{
118146
public:
@@ -151,6 +179,7 @@ class DynamicAvoidanceModule : public SceneModuleInterface
151179
bool is_collision_left{false};
152180
bool should_be_avoided{false};
153181
std::vector<PathPointWithLaneId> ref_path_points_for_obj_poly;
182+
LatFeasiblePaths ego_lat_feasible_paths;
154183

155184
void update(
156185
const MinMaxValue & arg_lon_offset_to_avoid, const MinMaxValue & arg_lat_offset_to_avoid,
@@ -172,14 +201,18 @@ class DynamicAvoidanceModule : public SceneModuleInterface
172201
{
173202
}
174203
int max_count_{0};
175-
int min_count_{0};
204+
int min_count_{0}; // TODO(murooka): The sign needs to be opposite?
176205

177206
void initialize() { current_uuids_.clear(); }
178207
void updateObject(const std::string & uuid, const DynamicAvoidanceObject & object)
179208
{
180209
// add/update object
181210
if (object_map_.count(uuid) != 0) {
211+
const auto prev_object = object_map_.at(uuid);
182212
object_map_.at(uuid) = object;
213+
// TODO(murooka) refactor this. Counter can be moved to DynamicObject,
214+
// and TargetObjectsManager can be removed.
215+
object_map_.at(uuid).ego_lat_feasible_paths = prev_object.ego_lat_feasible_paths;
183216
} else {
184217
object_map_.emplace(uuid, object);
185218
}
@@ -195,14 +228,12 @@ class DynamicAvoidanceModule : public SceneModuleInterface
195228
current_uuids_.push_back(uuid);
196229
}
197230

198-
void finalize()
231+
void finalize(const LatFeasiblePaths & ego_lat_feasible_paths)
199232
{
200233
// decrease counter for not updated uuids
201234
std::vector<std::string> not_updated_uuids;
202235
for (const auto & object : object_map_) {
203-
if (
204-
std::find(current_uuids_.begin(), current_uuids_.end(), object.first) ==
205-
current_uuids_.end()) {
236+
if (!isInVector(object.first, current_uuids_)) {
206237
not_updated_uuids.push_back(object.first);
207238
}
208239
}
@@ -214,45 +245,46 @@ class DynamicAvoidanceModule : public SceneModuleInterface
214245
}
215246
}
216247

217-
// remove objects whose counter is lower than threshold
218-
std::vector<std::string> obsolete_uuids;
248+
// update valid object uuids and its variable
219249
for (const auto & counter : counter_map_) {
220-
if (counter.second < min_count_) {
221-
obsolete_uuids.push_back(counter.first);
250+
if (!isInVector(counter.first, valid_object_uuids_) && max_count_ <= counter.second) {
251+
valid_object_uuids_.push_back(counter.first);
252+
object_map_.at(counter.first).ego_lat_feasible_paths = ego_lat_feasible_paths;
222253
}
223254
}
224-
for (const auto & obsolete_uuid : obsolete_uuids) {
225-
counter_map_.erase(obsolete_uuid);
226-
object_map_.erase(obsolete_uuid);
255+
valid_object_uuids_.erase(
256+
std::remove_if(
257+
valid_object_uuids_.begin(), valid_object_uuids_.end(),
258+
[&](const auto & uuid) {
259+
return counter_map_.count(uuid) == 0 || counter_map_.at(uuid) < max_count_;
260+
}),
261+
valid_object_uuids_.end());
262+
263+
// remove objects whose counter is lower than threshold
264+
const auto counter_map_keys = getAllKeys(counter_map_);
265+
for (const auto & key : counter_map_keys) {
266+
if (counter_map_.at(key) < min_count_) {
267+
counter_map_.erase(key);
268+
object_map_.erase(key);
269+
}
227270
}
228271
}
229272
std::vector<DynamicAvoidanceObject> getValidObjects() const
230273
{
231-
std::vector<DynamicAvoidanceObject> objects;
232-
for (const auto & object : object_map_) {
233-
if (counter_map_.count(object.first) != 0) {
234-
if (max_count_ <= counter_map_.at(object.first)) {
235-
objects.push_back(object.second);
236-
}
274+
std::vector<DynamicAvoidanceObject> valid_objects;
275+
for (const auto & valid_object_uuid : valid_object_uuids_) {
276+
if (object_map_.count(valid_object_uuid) == 0) {
277+
std::cerr
278+
<< "[DynamicAvoidance] Internal calculation has an error when getting valid objects."
279+
<< std::endl;
280+
continue;
237281
}
282+
valid_objects.push_back(object_map_.at(valid_object_uuid));
238283
}
239-
return objects;
240-
}
241-
std::optional<DynamicAvoidanceObject> getValidObject(const std::string & uuid) const
242-
{
243-
// add/update object
244-
if (counter_map_.count(uuid) == 0) {
245-
return std::nullopt;
246-
}
247-
if (counter_map_.at(uuid) < max_count_) {
248-
return std::nullopt;
249-
}
250-
if (object_map_.count(uuid) == 0) {
251-
return std::nullopt;
252-
}
253-
return object_map_.at(uuid);
284+
285+
return valid_objects;
254286
}
255-
void updateObject(
287+
void updateObjectVariables(
256288
const std::string & uuid, const MinMaxValue & lon_offset_to_avoid,
257289
const MinMaxValue & lat_offset_to_avoid, const bool is_collision_left,
258290
const bool should_be_avoided,
@@ -269,6 +301,7 @@ class DynamicAvoidanceModule : public SceneModuleInterface
269301
// NOTE: positive is for meeting entry condition, and negative is for exiting.
270302
std::unordered_map<std::string, int> counter_map_;
271303
std::unordered_map<std::string, DynamicAvoidanceObject> object_map_;
304+
std::vector<std::string> valid_object_uuids_{};
272305
};
273306

274307
struct DecisionWithReason
@@ -319,6 +352,8 @@ class DynamicAvoidanceModule : public SceneModuleInterface
319352

320353
bool isLabelTargetObstacle(const uint8_t label) const;
321354
void updateTargetObjects();
355+
LatFeasiblePaths generateLateralFeasiblePaths(
356+
const geometry_msgs::msg::Pose & ego_pose, const double ego_vel) const;
322357
void updateRefPathBeforeLaneChange(const std::vector<PathPointWithLaneId> & ego_ref_path_points);
323358
bool willObjectCutIn(
324359
const std::vector<PathPointWithLaneId> & ego_path, const PredictedPath & predicted_path,

0 commit comments

Comments
 (0)