Skip to content

Commit c9f2203

Browse files
Merge pull request #1042 from tier4/beta-to-tier4-main-sync
chore: sync beta branch beta/v0.17.0 with tier4/main
2 parents eb73feb + ceb1ce1 commit c9f2203

File tree

215 files changed

+8709
-4289
lines changed

Some content is hidden

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

215 files changed

+8709
-4289
lines changed

.github/labeler.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,7 @@
3131
- planning/**/*
3232
"component:sensing":
3333
- sensing/**/*
34-
"component:simulator":
34+
"component:simulation":
3535
- simulator/**/*
3636
"component:system":
3737
- system/**/*

.github/sync-files.yaml

-2
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,6 @@
1212
- source: .github/PULL_REQUEST_TEMPLATE/standard-change.md
1313
- source: .github/dependabot.yaml
1414
- source: .github/stale.yml
15-
pre-commands: |
16-
sd "staleLabel: stale" "staleLabel: status:stale" {source}
1715
- source: .github/workflows/cancel-previous-workflows.yaml
1816
- source: .github/workflows/github-release.yaml
1917
- source: .github/workflows/pre-commit.yaml

common/autoware_auto_perception_rviz_plugin/include/object_detection/predicted_objects_display.hpp

+33
Original file line numberDiff line numberDiff line change
@@ -24,9 +24,11 @@
2424

2525
#include <condition_variable>
2626
#include <list>
27+
#include <queue>
2728
#include <set>
2829
#include <string>
2930
#include <unordered_map>
31+
#include <utility>
3032
#include <vector>
3133

3234
namespace autoware
@@ -45,10 +47,31 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC PredictedObjectsDisplay
4547
using PredictedObjects = autoware_auto_perception_msgs::msg::PredictedObjects;
4648

4749
PredictedObjectsDisplay();
50+
~PredictedObjectsDisplay()
51+
{
52+
{
53+
std::unique_lock<std::mutex> lock(queue_mutex);
54+
should_terminate = true;
55+
}
56+
condition.notify_all();
57+
for (std::thread & active_thread : threads) {
58+
active_thread.join();
59+
}
60+
threads.clear();
61+
}
4862

4963
private:
5064
void processMessage(PredictedObjects::ConstSharedPtr msg) override;
5165

66+
void queueJob(std::function<void()> job)
67+
{
68+
{
69+
std::unique_lock<std::mutex> lock(queue_mutex);
70+
jobs.push(std::move(job));
71+
}
72+
condition.notify_one();
73+
}
74+
5275
boost::uuids::uuid to_boost_uuid(const unique_identifier_msgs::msg::UUID & uuid_msg)
5376
{
5477
const std::string uuid_str = uuid_to_string(uuid_msg);
@@ -100,6 +123,8 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC PredictedObjectsDisplay
100123
PredictedObjects::ConstSharedPtr msg);
101124
void workerThread();
102125

126+
void messageProcessorThreadJob();
127+
103128
void update(float wall_dt, float ros_dt) override;
104129

105130
std::unordered_map<boost::uuids::uuid, int32_t, boost::hash<boost::uuids::uuid>> id_map;
@@ -108,6 +133,14 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC PredictedObjectsDisplay
108133
int32_t marker_id = 0;
109134
const int32_t PATH_ID_CONSTANT = 1e3;
110135

136+
// max_num_threads: number of threads created in the thread pool, hard-coded to be 1;
137+
int max_num_threads;
138+
139+
bool should_terminate{false};
140+
std::mutex queue_mutex;
141+
std::vector<std::thread> threads;
142+
std::queue<std::function<void()>> jobs;
143+
111144
PredictedObjects::ConstSharedPtr msg;
112145
bool consumed{false};
113146
std::mutex mutex;

common/autoware_auto_perception_rviz_plugin/src/object_detection/predicted_objects_display.cpp

+31-14
Original file line numberDiff line numberDiff line change
@@ -25,27 +25,44 @@ namespace object_detection
2525
{
2626
PredictedObjectsDisplay::PredictedObjectsDisplay() : ObjectPolygonDisplayBase("tracks")
2727
{
28-
std::thread worker(&PredictedObjectsDisplay::workerThread, this);
29-
worker.detach();
28+
max_num_threads = 1; // hard code the number of threads to be created
29+
30+
for (int ii = 0; ii < max_num_threads; ++ii) {
31+
threads.emplace_back(std::thread(&PredictedObjectsDisplay::workerThread, this));
32+
}
3033
}
3134

3235
void PredictedObjectsDisplay::workerThread()
33-
{
36+
{ // A standard working thread that waiting for jobs
3437
while (true) {
35-
std::unique_lock<std::mutex> lock(mutex);
36-
condition.wait(lock, [this] { return this->msg; });
38+
std::function<void()> job;
39+
{
40+
std::unique_lock<std::mutex> lock(queue_mutex);
41+
condition.wait(lock, [this] { return !jobs.empty() || should_terminate; });
42+
if (should_terminate) {
43+
return;
44+
}
45+
job = jobs.front();
46+
jobs.pop();
47+
}
48+
job();
49+
}
50+
}
3751

38-
auto tmp_msg = this->msg;
39-
this->msg.reset();
52+
void PredictedObjectsDisplay::messageProcessorThreadJob()
53+
{
54+
// Receiving
55+
std::unique_lock<std::mutex> lock(mutex);
56+
auto tmp_msg = this->msg;
57+
this->msg.reset();
58+
lock.unlock();
4059

41-
lock.unlock();
60+
auto tmp_markers = createMarkers(tmp_msg);
4261

43-
auto tmp_markers = createMarkers(tmp_msg);
44-
lock.lock();
45-
markers = tmp_markers;
62+
lock.lock();
63+
markers = tmp_markers;
4664

47-
consumed = true;
48-
}
65+
consumed = true;
4966
}
5067

5168
std::vector<visualization_msgs::msg::Marker::SharedPtr> PredictedObjectsDisplay::createMarkers(
@@ -188,7 +205,7 @@ void PredictedObjectsDisplay::processMessage(PredictedObjects::ConstSharedPtr ms
188205
std::unique_lock<std::mutex> lock(mutex);
189206

190207
this->msg = msg;
191-
condition.notify_one();
208+
queueJob(std::bind(&PredictedObjectsDisplay::messageProcessorThreadJob, this));
192209
}
193210

194211
void PredictedObjectsDisplay::update(float wall_dt, float ros_dt)

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

+2-1
Original file line numberDiff line numberDiff line change
@@ -168,6 +168,7 @@ T removeOverlapPoints(const T & points, const size_t start_idx = 0)
168168
}
169169

170170
T dst;
171+
dst.reserve(points.size());
171172

172173
for (size_t i = 0; i <= start_idx; ++i) {
173174
dst.push_back(points.at(i));
@@ -1251,7 +1252,7 @@ calcLongitudinalOffsetPose<std::vector<autoware_auto_planning_msgs::msg::Traject
12511252
* @param offset length of offset from source point
12521253
* @param set_orientation_from_position_direction set orientation by spherical interpolation if
12531254
* false
1254-
* @return offset pase
1255+
* @return offset pose
12551256
*/
12561257
template <class T>
12571258
boost::optional<geometry_msgs::msg::Pose> calcLongitudinalOffsetPose(
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,77 @@
1+
// Copyright 2023 TIER IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#include "motion_utils/trajectory/trajectory.hpp"
16+
17+
#include <gtest/gtest.h>
18+
#include <gtest/internal/gtest-port.h>
19+
#include <tf2/LinearMath/Quaternion.h>
20+
21+
#include <random>
22+
23+
namespace
24+
{
25+
using autoware_auto_planning_msgs::msg::Trajectory;
26+
using tier4_autoware_utils::createPoint;
27+
using tier4_autoware_utils::createQuaternionFromRPY;
28+
29+
constexpr double epsilon = 1e-6;
30+
31+
geometry_msgs::msg::Pose createPose(
32+
double x, double y, double z, double roll, double pitch, double yaw)
33+
{
34+
geometry_msgs::msg::Pose p;
35+
p.position = createPoint(x, y, z);
36+
p.orientation = createQuaternionFromRPY(roll, pitch, yaw);
37+
return p;
38+
}
39+
40+
template <class T>
41+
T generateTestTrajectory(
42+
const size_t num_points, const double point_interval, const double vel = 0.0,
43+
const double init_theta = 0.0, const double delta_theta = 0.0)
44+
{
45+
using Point = typename T::_points_type::value_type;
46+
47+
T traj;
48+
for (size_t i = 0; i < num_points; ++i) {
49+
const double theta = init_theta + i * delta_theta;
50+
const double x = i * point_interval * std::cos(theta);
51+
const double y = i * point_interval * std::sin(theta);
52+
53+
Point p;
54+
p.pose = createPose(x, y, 0.0, 0.0, 0.0, theta);
55+
p.longitudinal_velocity_mps = vel;
56+
traj.points.push_back(p);
57+
}
58+
59+
return traj;
60+
}
61+
} // namespace
62+
63+
TEST(trajectory_benchmark, DISABLED_calcLateralOffset)
64+
{
65+
std::random_device r;
66+
std::default_random_engine e1(r());
67+
std::uniform_real_distribution<double> uniform_dist(0.0, 1000.0);
68+
69+
using motion_utils::calcLateralOffset;
70+
71+
const auto traj = generateTestTrajectory<Trajectory>(1000, 1.0, 0.0, 0.0, 0.1);
72+
constexpr auto nb_iteration = 10000;
73+
for (auto i = 0; i < nb_iteration; ++i) {
74+
const auto point = createPoint(uniform_dist(e1), uniform_dist(e1), 0.0);
75+
calcLateralOffset(traj.points, point);
76+
}
77+
}

control/lane_departure_checker/include/lane_departure_checker/lane_departure_checker.hpp

+10-5
Original file line numberDiff line numberDiff line change
@@ -29,6 +29,7 @@
2929
#include <geometry_msgs/msg/twist_stamped.hpp>
3030
#include <nav_msgs/msg/odometry.hpp>
3131

32+
#include <boost/geometry/index/rtree.hpp>
3233
#include <boost/optional.hpp>
3334

3435
#include <lanelet2_core/LaneletMap.h>
@@ -46,7 +47,9 @@ using autoware_auto_planning_msgs::msg::TrajectoryPoint;
4647
using autoware_planning_msgs::msg::LaneletRoute;
4748
using tier4_autoware_utils::LinearRing2d;
4849
using tier4_autoware_utils::PoseDeviation;
50+
using tier4_autoware_utils::Segment2d;
4951
using TrajectoryPoints = std::vector<TrajectoryPoint>;
52+
typedef boost::geometry::index::rtree<Segment2d, boost::geometry::index::rstar<16>> SegmentRtree;
5053

5154
struct Param
5255
{
@@ -137,13 +140,15 @@ class LaneDepartureChecker
137140
const lanelet::ConstLanelets & candidate_lanelets,
138141
const std::vector<LinearRing2d> & vehicle_footprints);
139142

143+
double calcMaxSearchLengthForBoundaries(const Trajectory & trajectory) const;
144+
145+
static SegmentRtree extractUncrossableBoundaries(
146+
const lanelet::LaneletMap & lanelet_map, const geometry_msgs::msg::Point & ego_point,
147+
const double max_search_length, const std::vector<std::string> & boundary_types_to_detect);
148+
140149
static bool willCrossBoundary(
141-
const lanelet::ConstLanelets & candidate_lanelets,
142150
const std::vector<LinearRing2d> & vehicle_footprints,
143-
const std::vector<std::string> & boundary_types_to_detects);
144-
145-
static bool isCrossingRoadBorder(
146-
const lanelet::BasicLineString2d & road_border, const std::vector<LinearRing2d> & footprints);
151+
const SegmentRtree & uncrossable_segments);
147152
};
148153
} // namespace lane_departure_checker
149154

0 commit comments

Comments
 (0)