Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

chore: sync upstream #1034

Merged
merged 83 commits into from
Nov 22, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
83 commits
Select commit Hold shift + click to select a range
b607e5c
feat(intersection): rectify initial accel/velocity profile in ego vel…
soblin Nov 8, 2023
c6d6fc1
fix: add_ros_test to add_launch_test (#5486)
kminoda Nov 8, 2023
3462f27
refactor(behavior_path_planner): remove status_.pull_over_lanes (#5520)
kyoichi-sugahara Nov 8, 2023
3e8c7bf
build(lidar_apollo_segmentation_tvm and lidar_apollo_segmentation_tvm…
lexavtanke Nov 8, 2023
e3f8a37
refactor(tier4_planning_launch): align argument name (#5505)
satoshi-ota Nov 8, 2023
56d804f
refactor(system_error_monitor): hide error log in no-fault condition …
TakaHoribe Nov 9, 2023
90f873c
feat(behavior_path_planner): add option to insert zero velocity to th…
kyoichi-sugahara Nov 9, 2023
6bfb0e5
refactor(start_planner): support new interface (#5526)
kyoichi-sugahara Nov 9, 2023
c4c3841
refactor(goal_planner): support new interface (#5525)
satoshi-ota Nov 9, 2023
eb2eb58
refactor(gyro_odometer): rework parameters (#5243)
YuqiHuai Nov 9, 2023
62de92a
refactor(ar_tag_based_localizer): refactor `ar_tag_based_localizer` (…
SakodaShintaro Nov 9, 2023
7b71000
refactor(motion_utils): fix typo in calcLongitudinalOffsetPose return…
kyoichi-sugahara Nov 9, 2023
805933c
fix(simple_planning_simulator): set ego pitch to 0 if road slope is n…
danielsanchezaran Nov 9, 2023
b8bfaea
refactor(dynamic_avoidance): support new interface (#5527)
satoshi-ota Nov 9, 2023
eb7ccb8
refactor(mission_planner): use combineLaneletsShape in lanelet2_exten…
kosuke55 Nov 9, 2023
7a63e68
feat(controller): publish processing time (#5537)
TakaHoribe Nov 9, 2023
b4a05f6
fix(mission_planner): revert "refactor(mission_planner): use combineL…
kosuke55 Nov 9, 2023
da6281f
fix(tier4_planning_launch): obstacle_cruise_planner pipeline is not c…
takayuki5168 Nov 10, 2023
54020ff
fix(image_projection_based_fusion): add missing install (#5548)
wep21 Nov 10, 2023
20c8641
perf(motion_utils): faster removeOverlapPoints and calcLateralOffset …
maxime-clem Nov 10, 2023
dd2c3a7
refactor(goal_planner): separate thread safe data (#5493)
kosuke55 Nov 10, 2023
c2fc188
refactor(start_planner): refactor backward path calculation in StartP…
kyoichi-sugahara Nov 10, 2023
bde4eb8
build(lidar_centerpoint_tvm): remove artifacts download (#5367)
lexavtanke Nov 10, 2023
a1dfb07
refactor(perception_rviz_plugin): apply thread pool to manage detache…
Owen-Liuyuxuan Nov 11, 2023
567b9e5
feat(intersection): use the centerline position of first attention ar…
soblin Nov 13, 2023
cd06205
fix: scan ground filter document (#5552)
miursh Nov 13, 2023
1f861e8
feat(geo_pose_projector): use geo_pose_projector in eagleye (#5513)
kminoda Nov 13, 2023
c8b60f8
feat(simple_planning_simulator): add acceleration and steer command s…
kosuke55 Nov 13, 2023
dcbff10
fix(ndt_scan_matcher): make regularization process thread safe (#5550)
KYabuuchi Nov 13, 2023
54ff23a
test(obstacle_velocity_limiter): added test cases for particle model …
bupeshr Nov 13, 2023
387cb24
fix(sampling_based_planner): fix runtime error (#5490)
satoshi-ota Nov 13, 2023
cbbc7b7
docs(lane_change): stopping position when an object exists ahead (#5523)
kosuke55 Nov 13, 2023
db962b3
fix(detection_by_tracker): add ignore option for each label (#5473)
badai-nguyen Nov 13, 2023
d3ab218
feat(image_projection_based_fusion): enable to show iou value in roi_…
YoshiRi Nov 13, 2023
8eb858a
refactor(landmark_parser): refactored landmark manager (#5511)
SakodaShintaro Nov 13, 2023
450f832
feat(obstacle_cruise_planner): use obstacle velocity based obstacle p…
danielsanchezaran Nov 14, 2023
cadba46
refactor(side_shift): support new interface (#5556)
satoshi-ota Nov 14, 2023
9f43afc
refactor(goal_planner): add updateStatus and reduce variables (#5546)
kosuke55 Nov 14, 2023
b11496e
fix(simple_planning_simulator): change default value of manual gear, …
h-ohta Nov 14, 2023
1886731
fix(lane_change): fix object debug marker not having point (#5577)
zulfaqar-azmi-t4 Nov 14, 2023
7d71687
fix(avoidance): fix a bug regarding the nearest search (#5575)
yuki-takagi-66 Nov 14, 2023
5fe26c6
refactor(goal_planner): refactoring plan flow and add post process (#…
kosuke55 Nov 14, 2023
874c559
ci(labeler): rename simulator to simulation (#5580)
xmfcx Nov 14, 2023
2a53348
feat(motion_velocity_smoother): add motion_velocity_smoother's virtua…
takayuki5168 Nov 14, 2023
4d79d98
feat(localization): add `pose_instability_detector` (#5439)
SakodaShintaro Nov 15, 2023
5930a79
fix(drivable_area_expansion): fix bug when reusing previous path poin…
maxime-clem Nov 15, 2023
fe50118
refactor(pose_instability_detector, ar_tag_based_localizer): specify …
KYabuuchi Nov 15, 2023
2bc49ae
fix(detected_object_validation): add 3d pointcloud based validator (#…
badai-nguyen Nov 15, 2023
cdf4b77
fix(goal_planner): fix detection_polygons visualiztion (#5596)
kosuke55 Nov 15, 2023
cae657b
ci(sync-files): remove stale label pre-commands (#5597)
xmfcx Nov 15, 2023
9026da8
chore(run_out): add maintainer (#5598)
TomohitoAndo Nov 15, 2023
62c3419
fix(goal_planner): fix extending current lanes (#5595)
kosuke55 Nov 15, 2023
58b909f
fix(geo_pose_projector): fix -Werror=deprecated-declarations (#5599)
satoshi-ota Nov 16, 2023
f12df94
refactor(goal_planner): refactor select path (#5559)
kosuke55 Nov 16, 2023
8ea6094
feat(lane_departure_checker): better cubstones's search (#5582)
takayuki5168 Nov 16, 2023
8c69bba
build(tier4_perception_launch): add tracking_object_merger (#5602)
kminoda Nov 16, 2023
db03668
fix(avoidance): fix avoidance exit condition (#5592)
satoshi-ota Nov 16, 2023
cbc54cf
fix(avoidance): fix wrong reason for unavoidable situation (#5558)
satoshi-ota Nov 16, 2023
d808d04
refactor(radar_object_clustering): move radar object clustering param…
YoshiRi Nov 16, 2023
7b1e139
feat(radar_object_tracker): Change to use `use_radar_tracking_fusion`…
miursh Nov 16, 2023
bce0800
fix(avoidance): fix bug in shift lon distance calculation (#5557)
satoshi-ota Nov 16, 2023
20345f4
fix(avoidance): prevent sudden steering at avoidance maneuver (#5572)
satoshi-ota Nov 16, 2023
8753183
feat(out_of_lane): more stable decisions (#5197)
maxime-clem Nov 16, 2023
1b5ef95
refactor(goal_planner): add prev_data instead of status (#5561)
kosuke55 Nov 16, 2023
4d916dd
feat(goal_planner): keep margin against objects as possible (#5569)
kosuke55 Nov 16, 2023
9513782
feat(out_of_lane): improve reuse of previous decision (#5611)
maxime-clem Nov 16, 2023
1e65d39
refactor(start_planner): support new interface (#5606)
kyoichi-sugahara Nov 17, 2023
4d27fa4
fix(lane_change): regulate at the traffic light (#5457)
zulfaqar-azmi-t4 Nov 17, 2023
dd3e9fb
fix(start_planner, goal_planner): remove inappropriate reference valu…
kosuke55 Nov 17, 2023
14e5101
feat(component_state_monitor): monitor pose_estimator output (#5617)
kminoda Nov 20, 2023
93e45ac
fix(simple_planning_simulator): fix ego sign pitch problem (#5616)
danielsanchezaran Nov 20, 2023
9e99bfc
fix(utils): fix monotonic bound create logic (#5565)
satoshi-ota Nov 20, 2023
a800040
fix(lane_change): fix abort path (#5628)
rej55 Nov 20, 2023
3bb70d0
refactor(start_planner): add verbose parameter for debug print (#5622)
kyoichi-sugahara Nov 20, 2023
e5c4b08
refactor(goal_planner): add rss safety check function (#5620)
kosuke55 Nov 20, 2023
eb9c714
feat(goal_planner): prevent auto approval for unsafe path (#5621)
kosuke55 Nov 20, 2023
6c2d806
refactor(behavior_path_planner): separate drivable area functions (#5…
zulfaqar-azmi-t4 Nov 21, 2023
691ab78
perf(image_projection_based_fusion): replace std::bitset (#5603)
wep21 Nov 21, 2023
06af6c1
fix(bytetrack): fix uninteded roi value error due to casting int to u…
YoshiRi Nov 21, 2023
1ca01ce
fix(start_planner): fix logPullOutStatus format specifier (#5637)
kyoichi-sugahara Nov 21, 2023
de311a3
fix(goal_planner): fix prevent auto approval for unsafe path #5621 (#…
kosuke55 Nov 21, 2023
c522965
fix(out_of_lane): prevent "Same points are given" error message (#5643)
maxime-clem Nov 21, 2023
635e399
build(lidar_centerpoint_tvm): add missing tf2_sensor_msgs depedency (…
esteve Nov 21, 2023
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion .github/labeler.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@
- planning/**/*
"component:sensing":
- sensing/**/*
"component:simulator":
"component:simulation":
- simulator/**/*
"component:system":
- system/**/*
Expand Down
2 changes: 0 additions & 2 deletions .github/sync-files.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,6 @@
- source: .github/PULL_REQUEST_TEMPLATE/standard-change.md
- source: .github/dependabot.yaml
- source: .github/stale.yml
pre-commands: |
sd "staleLabel: stale" "staleLabel: status:stale" {source}
- source: .github/workflows/cancel-previous-workflows.yaml
- source: .github/workflows/github-release.yaml
- source: .github/workflows/pre-commit.yaml
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,9 +24,11 @@

#include <condition_variable>
#include <list>
#include <queue>
#include <set>
#include <string>
#include <unordered_map>
#include <utility>
#include <vector>

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

PredictedObjectsDisplay();
~PredictedObjectsDisplay()
{
{
std::unique_lock<std::mutex> lock(queue_mutex);
should_terminate = true;
}
condition.notify_all();
for (std::thread & active_thread : threads) {
active_thread.join();
}
threads.clear();
}

private:
void processMessage(PredictedObjects::ConstSharedPtr msg) override;

void queueJob(std::function<void()> job)
{
{
std::unique_lock<std::mutex> lock(queue_mutex);
jobs.push(std::move(job));
}
condition.notify_one();
}

boost::uuids::uuid to_boost_uuid(const unique_identifier_msgs::msg::UUID & uuid_msg)
{
const std::string uuid_str = uuid_to_string(uuid_msg);
Expand Down Expand Up @@ -100,6 +123,8 @@ class AUTOWARE_AUTO_PERCEPTION_RVIZ_PLUGIN_PUBLIC PredictedObjectsDisplay
PredictedObjects::ConstSharedPtr msg);
void workerThread();

void messageProcessorThreadJob();

void update(float wall_dt, float ros_dt) override;

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

// max_num_threads: number of threads created in the thread pool, hard-coded to be 1;
int max_num_threads;

bool should_terminate{false};
std::mutex queue_mutex;
std::vector<std::thread> threads;
std::queue<std::function<void()>> jobs;

PredictedObjects::ConstSharedPtr msg;
bool consumed{false};
std::mutex mutex;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,27 +25,44 @@ namespace object_detection
{
PredictedObjectsDisplay::PredictedObjectsDisplay() : ObjectPolygonDisplayBase("tracks")
{
std::thread worker(&PredictedObjectsDisplay::workerThread, this);
worker.detach();
max_num_threads = 1; // hard code the number of threads to be created

for (int ii = 0; ii < max_num_threads; ++ii) {
threads.emplace_back(std::thread(&PredictedObjectsDisplay::workerThread, this));
}
}

void PredictedObjectsDisplay::workerThread()
{
{ // A standard working thread that waiting for jobs
while (true) {
std::unique_lock<std::mutex> lock(mutex);
condition.wait(lock, [this] { return this->msg; });
std::function<void()> job;
{
std::unique_lock<std::mutex> lock(queue_mutex);
condition.wait(lock, [this] { return !jobs.empty() || should_terminate; });
if (should_terminate) {
return;
}
job = jobs.front();
jobs.pop();
}
job();
}
}

auto tmp_msg = this->msg;
this->msg.reset();
void PredictedObjectsDisplay::messageProcessorThreadJob()
{
// Receiving
std::unique_lock<std::mutex> lock(mutex);
auto tmp_msg = this->msg;
this->msg.reset();
lock.unlock();

lock.unlock();
auto tmp_markers = createMarkers(tmp_msg);

auto tmp_markers = createMarkers(tmp_msg);
lock.lock();
markers = tmp_markers;
lock.lock();
markers = tmp_markers;

consumed = true;
}
consumed = true;
}

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

this->msg = msg;
condition.notify_one();
queueJob(std::bind(&PredictedObjectsDisplay::messageProcessorThreadJob, this));
}

void PredictedObjectsDisplay::update(float wall_dt, float ros_dt)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -168,6 +168,7 @@ T removeOverlapPoints(const T & points, const size_t start_idx = 0)
}

T dst;
dst.reserve(points.size());

for (size_t i = 0; i <= start_idx; ++i) {
dst.push_back(points.at(i));
Expand Down Expand Up @@ -1251,7 +1252,7 @@ calcLongitudinalOffsetPose<std::vector<autoware_auto_planning_msgs::msg::Traject
* @param offset length of offset from source point
* @param set_orientation_from_position_direction set orientation by spherical interpolation if
* false
* @return offset pase
* @return offset pose
*/
template <class T>
boost::optional<geometry_msgs::msg::Pose> calcLongitudinalOffsetPose(
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,77 @@
// Copyright 2023 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include "motion_utils/trajectory/trajectory.hpp"

#include <gtest/gtest.h>
#include <gtest/internal/gtest-port.h>
#include <tf2/LinearMath/Quaternion.h>

#include <random>

namespace
{
using autoware_auto_planning_msgs::msg::Trajectory;
using tier4_autoware_utils::createPoint;
using tier4_autoware_utils::createQuaternionFromRPY;

constexpr double epsilon = 1e-6;

geometry_msgs::msg::Pose createPose(
double x, double y, double z, double roll, double pitch, double yaw)
{
geometry_msgs::msg::Pose p;
p.position = createPoint(x, y, z);
p.orientation = createQuaternionFromRPY(roll, pitch, yaw);
return p;
}

template <class T>
T generateTestTrajectory(
const size_t num_points, const double point_interval, const double vel = 0.0,
const double init_theta = 0.0, const double delta_theta = 0.0)
{
using Point = typename T::_points_type::value_type;

T traj;
for (size_t i = 0; i < num_points; ++i) {
const double theta = init_theta + i * delta_theta;
const double x = i * point_interval * std::cos(theta);
const double y = i * point_interval * std::sin(theta);

Point p;
p.pose = createPose(x, y, 0.0, 0.0, 0.0, theta);
p.longitudinal_velocity_mps = vel;
traj.points.push_back(p);
}

return traj;
}
} // namespace

TEST(trajectory_benchmark, DISABLED_calcLateralOffset)
{
std::random_device r;
std::default_random_engine e1(r());
std::uniform_real_distribution<double> uniform_dist(0.0, 1000.0);

using motion_utils::calcLateralOffset;

const auto traj = generateTestTrajectory<Trajectory>(1000, 1.0, 0.0, 0.0, 0.1);
constexpr auto nb_iteration = 10000;
for (auto i = 0; i < nb_iteration; ++i) {
const auto point = createPoint(uniform_dist(e1), uniform_dist(e1), 0.0);
calcLateralOffset(traj.points, point);
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@
#include <geometry_msgs/msg/twist_stamped.hpp>
#include <nav_msgs/msg/odometry.hpp>

#include <boost/geometry/index/rtree.hpp>
#include <boost/optional.hpp>

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

struct Param
{
Expand Down Expand Up @@ -137,13 +140,15 @@ class LaneDepartureChecker
const lanelet::ConstLanelets & candidate_lanelets,
const std::vector<LinearRing2d> & vehicle_footprints);

double calcMaxSearchLengthForBoundaries(const Trajectory & trajectory) const;

static SegmentRtree extractUncrossableBoundaries(
const lanelet::LaneletMap & lanelet_map, const geometry_msgs::msg::Point & ego_point,
const double max_search_length, const std::vector<std::string> & boundary_types_to_detect);

static bool willCrossBoundary(
const lanelet::ConstLanelets & candidate_lanelets,
const std::vector<LinearRing2d> & vehicle_footprints,
const std::vector<std::string> & boundary_types_to_detects);

static bool isCrossingRoadBorder(
const lanelet::BasicLineString2d & road_border, const std::vector<LinearRing2d> & footprints);
const SegmentRtree & uncrossable_segments);
};
} // namespace lane_departure_checker

Expand Down
Loading
Loading