Skip to content

Commit 9baac21

Browse files
authored
Merge branch 'main' into traffic-light-classifier
2 parents 9ef5757 + 3b0c254 commit 9baac21

File tree

42 files changed

+481
-212
lines changed

Some content is hidden

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

42 files changed

+481
-212
lines changed

common/tier4_logging_level_configure_rviz_plugin/config/logger_config.yaml

+8
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,14 @@ Planning:
3838
- node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner
3939
logger_name: planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner.avoidance
4040

41+
behavior_path_planner_goal_planner:
42+
- node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner
43+
logger_name: planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner.goal_planner
44+
45+
behavior_path_planner_start_planner:
46+
- node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner
47+
logger_name: planning.scenario_planning.lane_driving.behavior_planning.behavior_path_planner.start_planner
48+
4149
behavior_path_avoidance_by_lane_change:
4250
- node_name: /planning/scenario_planning/lane_driving/behavior_planning/behavior_path_planner
4351
logger_name: lane_change.AVOIDANCE_BY_LANE_CHANGE
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,79 @@
1+
{
2+
"$schema": "http://json-schema.org/draft-07/schema#",
3+
"title": "Parameters for lane_departure_checker",
4+
"type": "object",
5+
"definitions": {
6+
"lane_departure_checker": {
7+
"type": "object",
8+
"properties": {
9+
"footprint_margin_scale": {
10+
"type": "number",
11+
"default": 1.0,
12+
"description": "Coefficient for expanding footprint margin. Multiplied by 1 standard deviation."
13+
},
14+
"resample_interval": {
15+
"type": "number",
16+
"default": 0.3,
17+
"description": "Minimum Euclidean distance between points when resample trajectory.[m]."
18+
},
19+
"max_deceleration": {
20+
"type": "number",
21+
"default": 2.8,
22+
"description": "Maximum deceleration when calculating braking distance."
23+
},
24+
"delay_time": {
25+
"type": "number",
26+
"default": 1.3,
27+
"description": "Delay time which took to actuate brake when calculating braking distance. [second]."
28+
},
29+
"max_lateral_deviation": {
30+
"type": "number",
31+
"default": 2.0,
32+
"description": "Maximum lateral deviation in vehicle coordinate. [m]."
33+
},
34+
"max_longitudinal_deviation": {
35+
"type": "number",
36+
"default": 2.0,
37+
"description": "Maximum longitudinal deviation in vehicle coordinate. [m]."
38+
},
39+
"max_yaw_deviation_deg": {
40+
"type": "number",
41+
"default": 60.0,
42+
"description": "Maximum ego yaw deviation from trajectory. [deg]."
43+
},
44+
"ego_nearest_dist_threshold": {
45+
"type": "number"
46+
},
47+
"ego_nearest_yaw_threshold": {
48+
"type": "number"
49+
},
50+
"min_braking_distance": {
51+
"type": "number"
52+
}
53+
},
54+
"required": [
55+
"footprint_margin_scale",
56+
"resample_interval",
57+
"max_deceleration",
58+
"max_lateral_deviation",
59+
"max_longitudinal_deviation",
60+
"max_yaw_deviation_deg",
61+
"ego_nearest_dist_threshold",
62+
"ego_nearest_yaw_threshold",
63+
"min_braking_distance"
64+
]
65+
}
66+
},
67+
"properties": {
68+
"/**": {
69+
"type": "object",
70+
"properties": {
71+
"ros__parameters": {
72+
"$ref": "#/definitions/lane_departure_checker"
73+
}
74+
},
75+
"required": ["ros__parameters"]
76+
}
77+
},
78+
"required": ["/**"]
79+
}

control/mpc_lateral_controller/src/lowpass_filter.cpp

+2-4
Original file line numberDiff line numberDiff line change
@@ -120,10 +120,8 @@ bool filt_vector(const int num, std::vector<double> & u)
120120
double tmp = 0.0;
121121
int num_tmp = 0;
122122
double count = 0;
123-
if (i - num < 0) {
124-
num_tmp = i;
125-
} else if (i + num > static_cast<int>(u.size()) - 1) {
126-
num_tmp = static_cast<int>(u.size()) - i - 1;
123+
if ((i - num < 0) || (i + num > static_cast<int>(u.size()) - 1)) {
124+
num_tmp = std::min(i, static_cast<int>(u.size()) - i - 1);
127125
} else {
128126
num_tmp = num;
129127
}

control/mpc_lateral_controller/test/test_lowpass_filter.cpp

+24
Original file line numberDiff line numberDiff line change
@@ -61,6 +61,30 @@ TEST(TestLowpassFilter, MoveAverageFilter)
6161
EXPECT_EQ(filtered_vec[4], 23.0 / 3);
6262
EXPECT_EQ(filtered_vec[5], original_vec[5]);
6363
}
64+
{
65+
const int window_size = 3;
66+
const std::vector<double> original_vec = {1.0, 1.0, 1.0, 1.0};
67+
std::vector<double> filtered_vec = original_vec;
68+
EXPECT_TRUE(MoveAverageFilter::filt_vector(window_size, filtered_vec));
69+
ASSERT_EQ(filtered_vec.size(), original_vec.size());
70+
EXPECT_EQ(filtered_vec[0], original_vec[0]);
71+
EXPECT_EQ(filtered_vec[1], 1.0);
72+
EXPECT_EQ(filtered_vec[2], 1.0);
73+
EXPECT_EQ(filtered_vec[3], original_vec[3]);
74+
}
75+
{
76+
const int window_size = 4;
77+
const std::vector<double> original_vec = {1.0, 3.0, 4.0, 6.0, 7.0, 10.0};
78+
std::vector<double> filtered_vec = original_vec;
79+
EXPECT_TRUE(MoveAverageFilter::filt_vector(window_size, filtered_vec));
80+
ASSERT_EQ(filtered_vec.size(), original_vec.size());
81+
EXPECT_EQ(filtered_vec[0], original_vec[0]);
82+
EXPECT_EQ(filtered_vec[1], 8.0 / 3);
83+
EXPECT_EQ(filtered_vec[2], 21.0 / 5);
84+
EXPECT_EQ(filtered_vec[3], 30.0 / 5);
85+
EXPECT_EQ(filtered_vec[4], 23.0 / 3);
86+
EXPECT_EQ(filtered_vec[5], original_vec[5]);
87+
}
6488
}
6589
TEST(TestLowpassFilter, Butterworth2dFilter)
6690
{

launch/tier4_perception_launch/launch/traffic_light_recognition/traffic_light_node_container.launch.py

+15-4
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,8 @@ def add_launch_arg(name: str, default_value=None, description=None):
4242
add_launch_arg("input/image", "/sensing/camera/traffic_light/image_raw")
4343
add_launch_arg("output/rois", "/perception/traffic_light_recognition/rois")
4444
add_launch_arg(
45-
"output/traffic_signals", "/perception/traffic_light_recognition/traffic_signals"
45+
"output/traffic_signals",
46+
"/perception/traffic_light_recognition/traffic_signals",
4647
)
4748

4849
# traffic_light_fine_detector
@@ -64,14 +65,20 @@ def add_launch_arg(name: str, default_value=None, description=None):
6465
add_launch_arg("classifier_type", "1")
6566
add_launch_arg(
6667
"classifier_model_path",
67-
os.path.join(classifier_share_dir, "data", "traffic_light_classifier_efficientNet_b1.onnx"),
68+
os.path.join(
69+
classifier_share_dir,
70+
"data",
71+
"traffic_light_classifier_efficientNet_b1.onnx",
72+
),
6873
)
6974
add_launch_arg(
70-
"classifier_label_path", os.path.join(classifier_share_dir, "data", "lamp_labels.txt")
75+
"classifier_label_path",
76+
os.path.join(classifier_share_dir, "data", "lamp_labels.txt"),
7177
)
7278
add_launch_arg("classifier_precision", "fp16")
7379
add_launch_arg("classifier_mean", "[123.675, 116.28, 103.53]")
7480
add_launch_arg("classifier_std", "[58.395, 57.12, 57.375]")
81+
add_launch_arg("backlight_threshold", "0.85")
7582

7683
add_launch_arg("use_intra_process", "False")
7784
add_launch_arg("use_multithread", "False")
@@ -102,6 +109,7 @@ def create_parameter_dict(*args):
102109
"classifier_precision",
103110
"classifier_mean",
104111
"classifier_std",
112+
"backlight_threshold",
105113
)
106114
],
107115
remappings=[
@@ -122,7 +130,10 @@ def create_parameter_dict(*args):
122130
("~/input/image", LaunchConfiguration("input/image")),
123131
("~/input/rois", LaunchConfiguration("output/rois")),
124132
("~/input/rough/rois", "detection/rough/rois"),
125-
("~/input/traffic_signals", LaunchConfiguration("output/traffic_signals")),
133+
(
134+
"~/input/traffic_signals",
135+
LaunchConfiguration("output/traffic_signals"),
136+
),
126137
("~/output/image", "debug/rois"),
127138
("~/output/image/compressed", "debug/rois/compressed"),
128139
("~/output/image/compressedDepth", "debug/rois/compressedDepth"),

localization/landmark_based_localizer/README.md

+1-62
Original file line numberDiff line numberDiff line change
@@ -43,68 +43,7 @@ So, if the 4 vertices are considered as forming a tetrahedron and its volume exc
4343

4444
## Map specifications
4545

46-
For this package to work correctly, the poses of the landmarks must be specified in the Lanelet2 map format that `map_loader` and `landmark_manager` can interpret.
47-
48-
The four vertices of a landmark are defined counterclockwise.
49-
50-
The order of the four vertices is defined as follows. In the coordinate system of a landmark,
51-
52-
- the x-axis is parallel to the vector from the first vertex to the second vertex
53-
- the y-axis is parallel to the vector from the second vertex to the third vertex
54-
55-
![lanelet2 data structure](./doc_image/lanelet2_data_structure.drawio.svg)
56-
57-
### Example of `lanelet2_map.osm`
58-
59-
The values provided below are placeholders.
60-
Ensure to input the correct coordinates corresponding to the actual location where the landmark is placed, such as `lat`, `lon`, `mgrs_code`, `local_x`, `local_y`.
61-
62-
For example, when using the AR tag, it would look like this.
63-
64-
```xml
65-
...
66-
67-
<node id="1" lat="35.8xxxxx" lon="139.6xxxxx">
68-
<tag k="mgrs_code" v="99XXX000000"/>
69-
<tag k="local_x" v="22.2356"/>
70-
<tag k="local_y" v="87.4506"/>
71-
<tag k="ele" v="2.1725"/>
72-
</node>
73-
<node id="2" lat="35.8xxxxx" lon="139.6xxxxx">
74-
<tag k="mgrs_code" v="99XXX000000"/>
75-
<tag k="local_x" v="22.639"/>
76-
<tag k="local_y" v="87.5886"/>
77-
<tag k="ele" v="2.5947"/>
78-
</node>
79-
<node id="3" lat="35.8xxxxx" lon="139.6xxxxx">
80-
<tag k="mgrs_code" v="99XXX000000"/>
81-
<tag k="local_x" v="22.2331"/>
82-
<tag k="local_y" v="87.4713"/>
83-
<tag k="ele" v="3.0208"/>
84-
</node>
85-
<node id="4" lat="35.8xxxxx" lon="139.6xxxxx">
86-
<tag k="mgrs_code" v="99XXX000000"/>
87-
<tag k="local_x" v="21.8298"/>
88-
<tag k="local_y" v="87.3332"/>
89-
<tag k="ele" v="2.5985"/>
90-
</node>
91-
92-
...
93-
94-
<way id="5">
95-
<nd ref="1"/>
96-
<nd ref="2"/>
97-
<nd ref="3"/>
98-
<nd ref="4"/>
99-
<tag k="type" v="pose_marker"/>
100-
<tag k="subtype" v="apriltag_16h5"/>
101-
<tag k="area" v="yes"/>
102-
<tag k="marker_id" v="0"/>
103-
</way>
104-
105-
...
106-
107-
```
46+
See <https://github.com/autowarefoundation/autoware_common/blob/main/tmp/lanelet2_extension/docs/lanelet2_format_extension.md#localization-landmarks>
10847

10948
## About `consider_orientation`
11049

localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.cpp

+7-7
Original file line numberDiff line numberDiff line change
@@ -142,7 +142,7 @@ ArTagBasedLocalizer::ArTagBasedLocalizer(const rclcpp::NodeOptions & options)
142142

143143
void ArTagBasedLocalizer::map_bin_callback(const HADMapBin::ConstSharedPtr & msg)
144144
{
145-
landmark_manager_.parse_landmarks(msg, "apriltag_16h5", this->get_logger());
145+
landmark_manager_.parse_landmarks(msg, "apriltag_16h5");
146146
const MarkerArray marker_msg = landmark_manager_.get_landmarks_as_marker_array_msg();
147147
mapped_tag_pose_pub_->publish(marker_msg);
148148
}
@@ -173,7 +173,7 @@ void ArTagBasedLocalizer::image_callback(const Image::ConstSharedPtr & msg)
173173
const Pose self_pose = interpolate_result.value().interpolated_pose.pose.pose;
174174

175175
// detect
176-
const std::vector<landmark_manager::Landmark> landmarks = detect_landmarks(msg);
176+
const std::vector<Landmark> landmarks = detect_landmarks(msg);
177177
if (landmarks.empty()) {
178178
return;
179179
}
@@ -183,7 +183,7 @@ void ArTagBasedLocalizer::image_callback(const Image::ConstSharedPtr & msg)
183183
PoseArray pose_array_msg;
184184
pose_array_msg.header.stamp = sensor_stamp;
185185
pose_array_msg.header.frame_id = "map";
186-
for (const landmark_manager::Landmark & landmark : landmarks) {
186+
for (const Landmark & landmark : landmarks) {
187187
const Pose detected_marker_on_map =
188188
tier4_autoware_utils::transformPose(landmark.pose, self_pose);
189189
pose_array_msg.poses.push_back(detected_marker_on_map);
@@ -293,7 +293,7 @@ std::vector<landmark_manager::Landmark> ArTagBasedLocalizer::detect_landmarks(
293293
cv_ptr->image.copyTo(in_image);
294294
} catch (cv_bridge::Exception & e) {
295295
RCLCPP_ERROR(this->get_logger(), "cv_bridge exception: %s", e.what());
296-
return std::vector<landmark_manager::Landmark>{};
296+
return std::vector<Landmark>{};
297297
}
298298

299299
// get transform from base_link to camera
@@ -303,15 +303,15 @@ std::vector<landmark_manager::Landmark> ArTagBasedLocalizer::detect_landmarks(
303303
tf_buffer_->lookupTransform("base_link", msg->header.frame_id, sensor_stamp);
304304
} catch (tf2::TransformException & ex) {
305305
RCLCPP_INFO(this->get_logger(), "Could not transform base_link to camera: %s", ex.what());
306-
return std::vector<landmark_manager::Landmark>{};
306+
return std::vector<Landmark>{};
307307
}
308308

309309
// detect
310310
std::vector<aruco::Marker> markers;
311311
detector_.detect(in_image, markers, cam_param_, marker_size_, false);
312312

313313
// parse
314-
std::vector<landmark_manager::Landmark> landmarks;
314+
std::vector<Landmark> landmarks;
315315

316316
for (aruco::Marker & marker : markers) {
317317
// convert marker pose to tf
@@ -327,7 +327,7 @@ std::vector<landmark_manager::Landmark> ArTagBasedLocalizer::detect_landmarks(
327327
const double distance = std::hypot(pose.position.x, pose.position.y, pose.position.z);
328328
if (distance <= distance_threshold_) {
329329
tf2::doTransform(pose, pose, transform_sensor_to_base_link);
330-
landmarks.push_back(landmark_manager::Landmark{std::to_string(marker.id), pose});
330+
landmarks.push_back(Landmark{std::to_string(marker.id), pose});
331331
}
332332

333333
// for debug, drawing the detected markers

localization/landmark_based_localizer/ar_tag_based_localizer/src/ar_tag_based_localizer.hpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -80,6 +80,7 @@ class ArTagBasedLocalizer : public rclcpp::Node
8080
using TransformStamped = geometry_msgs::msg::TransformStamped;
8181
using MarkerArray = visualization_msgs::msg::MarkerArray;
8282
using DiagnosticArray = diagnostic_msgs::msg::DiagnosticArray;
83+
using Landmark = landmark_manager::Landmark;
8384

8485
public:
8586
explicit ArTagBasedLocalizer(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
@@ -89,7 +90,7 @@ class ArTagBasedLocalizer : public rclcpp::Node
8990
void image_callback(const Image::ConstSharedPtr & msg);
9091
void cam_info_callback(const CameraInfo::ConstSharedPtr & msg);
9192
void ekf_pose_callback(const PoseWithCovarianceStamped::ConstSharedPtr & msg);
92-
std::vector<landmark_manager::Landmark> detect_landmarks(const Image::ConstSharedPtr & msg);
93+
std::vector<Landmark> detect_landmarks(const Image::ConstSharedPtr & msg);
9394

9495
// Parameters
9596
float marker_size_{};

localization/landmark_based_localizer/landmark_manager/include/landmark_manager/landmark_manager.hpp

+5-3
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,8 @@
1515
#ifndef LANDMARK_MANAGER__LANDMARK_MANAGER_HPP_
1616
#define LANDMARK_MANAGER__LANDMARK_MANAGER_HPP_
1717

18+
#include "lanelet2_extension/localization/landmark.hpp"
19+
1820
#include <rclcpp/rclcpp.hpp>
1921

2022
#include "autoware_auto_mapping_msgs/msg/had_map_bin.hpp"
@@ -40,13 +42,13 @@ class LandmarkManager
4042
public:
4143
void parse_landmarks(
4244
const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr & msg,
43-
const std::string & target_subtype, const rclcpp::Logger & logger);
45+
const std::string & target_subtype);
4446

4547
[[nodiscard]] visualization_msgs::msg::MarkerArray get_landmarks_as_marker_array_msg() const;
4648

4749
[[nodiscard]] geometry_msgs::msg::Pose calculate_new_self_pose(
48-
const std::vector<landmark_manager::Landmark> & detected_landmarks,
49-
const geometry_msgs::msg::Pose & self_pose, const bool consider_orientation) const;
50+
const std::vector<Landmark> & detected_landmarks, const geometry_msgs::msg::Pose & self_pose,
51+
const bool consider_orientation) const;
5052

5153
private:
5254
// To allow multiple landmarks with the same id to be registered on a vector_map,

0 commit comments

Comments
 (0)