Skip to content

Commit f3a26bc

Browse files
taikitanaka3TakaHoribemaxime-clemJoshua Whitleyniosus
authored
feat: add obstacle collision checker package (autowarefoundation#46)
* Back port .auto control packages (autowarefoundation#571) * Implement Lateral and Longitudinal Control Muxer * [autowarefoundation#570] Porting wf_simulator * [autowarefoundation#1189] Deactivate flaky test in 'trajectory_follower_nodes' * [autowarefoundation#1189] Fix flacky test in 'trajectory_follower_nodes/latlon_muxer' * [autowarefoundation#1057] Add osqp_interface package * [autowarefoundation#1057] Add library code for MPC-based lateral control * [autowarefoundation#1271] Use std::abs instead of abs * [autowarefoundation#1057] Implement Lateral Controller for Cargo ODD * [autowarefoundation#1246] Resolve "Test case names currently use snake_case but should be CamelCase" * [autowarefoundation#1325] Deactivate flaky smoke test in 'trajectory_follower_nodes' * [autowarefoundation#1058] Add library code of longitudinal controller * Fix build error for trajectory follower Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp> * Fix build error for trajectory follower nodes Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp> * [autowarefoundation#1272] Add AckermannControlCommand support to simple_planning_simulator * [autowarefoundation#1058] Add Longitudinal Controller node * [autowarefoundation#1058] Rename velocity_controller -> longitudinal_controller * [autowarefoundation#1058] Update CMakeLists.txt for the longitudinal_controller_node * [autowarefoundation#1058] Add smoke test python launch file * [autowarefoundation#1058] Use LowPassFilter1d from trajectory_follower * [autowarefoundation#1058] Use autoware_auto_msgs * [autowarefoundation#1058] Changes for .auto (debug msg tmp fix, common func, tf listener) * [autowarefoundation#1058] Remove unused parameters * [autowarefoundation#1058] Fix ros test * [autowarefoundation#1058] Rm default params from declare_parameters + use autoware types * [autowarefoundation#1058] Use default param file to setup NodeOptions in the ros test * [autowarefoundation#1058] Fix docstring * [autowarefoundation#1058] Replace receiving a Twist with a VehicleKinematicState * [autowarefoundation#1058] Change class variables format to m_ prefix * [autowarefoundation#1058] Fix plugin name of LongitudinalController in CMakeLists.txt * [autowarefoundation#1058] Fix copyright dates * [autowarefoundation#1058] Reorder includes * [autowarefoundation#1058] Add some tests (~89% coverage without disabling flaky tests) * [autowarefoundation#1058] Add more tests (90+% coverage without disabling flaky tests) * [autowarefoundation#1058] Use Float32MultiArrayDiagnostic message for debug and slope * [autowarefoundation#1058] Calculate wheel_base value from vehicle parameters * [autowarefoundation#1058] Cleanup redundant logger setting in tests * [autowarefoundation#1058] Set ROS_DOMAIN_ID when running tests to prevent CI failures * [autowarefoundation#1058] Remove TF listener and use published vehicle state instead * [autowarefoundation#1058] Change smoke tests to use autoware_testing * [autowarefoundation#1058] Add plotjuggler cfg for both lateral and longitudinal control * [autowarefoundation#1058] Improve design documents * [autowarefoundation#1058] Disable flaky test * [autowarefoundation#1058] Properly transform vehicle state in longitudinal node * [autowarefoundation#1058] Fix TF buffer of lateral controller * [autowarefoundation#1058] Tuning of lateral controller for LGSVL * [autowarefoundation#1058] Fix formating * [autowarefoundation#1058] Fix /tf_static sub to be transient_local * [autowarefoundation#1058] Fix yaw recalculation of reverse trajs in the lateral controller * modify trajectory_follower for galactic build Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com> * [autowarefoundation#1379] Update trajectory_follower * [autowarefoundation#1379] Update simple_planning_simulator * [autowarefoundation#1379] Update trajectory_follower_nodes * apply trajectory msg modification in control Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com> * move directory Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com> * remote control/trajectory_follower level dorectpry Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com> * remove .iv trajectory follower Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com> * use .auto trajectory_follower Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com> * remove .iv simple_planning_simulator & osqp_interface Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com> * use .iv simple_planning_simulator & osqp_interface Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com> * add tmp_autoware_auto_dependencies Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com> * tmporally add autoware_auto_msgs Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com> * apply .auto message split Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com> * fix build depend Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com> * fix packages using osqp * fix autoware_auto_geometry * ignore lint of some packages * ignore ament_lint of some packages * ignore lint/pre-commit of trajectory_follower_nodes * disable unit tests of some packages Co-authored-by: Maxime CLEMENT <maxime.clement@tier4.jp> Co-authored-by: Joshua Whitley <josh.whitley@autoware.org> Co-authored-by: Igor Bogoslavskyi <igor.bogoslavskyi@gmail.com> Co-authored-by: MIURA Yasuyuki <kokosabu@gmail.com> Co-authored-by: wep21 <border_goldenmarket@yahoo.co.jp> Co-authored-by: tomoya.kimura <tomoya.kimura@tier4.jp> * Fix no ground pointcloud topic name (autowarefoundation#733) Signed-off-by: j4tfwm6z <proj-jpntaxi@tier4.jp> Co-authored-by: j4tfwm6z <proj-jpntaxi@tier4.jp> * Update twist topic name (autowarefoundation#736) Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp> * fix/rename segmentation namespace (autowarefoundation#742) * rename segmentation directory * fix namespace: system stack * fix namespace: planning * fix namespace: control stack * fix namespace: perception stack * fix readme * ci(pre-commit): autofix Co-authored-by: Takamasa Horibe <horibe.takamasa@gmail.com> Co-authored-by: Maxime CLEMENT <maxime.clement@tier4.jp> Co-authored-by: Joshua Whitley <josh.whitley@autoware.org> Co-authored-by: Igor Bogoslavskyi <igor.bogoslavskyi@gmail.com> Co-authored-by: MIURA Yasuyuki <kokosabu@gmail.com> Co-authored-by: wep21 <border_goldenmarket@yahoo.co.jp> Co-authored-by: tomoya.kimura <tomoya.kimura@tier4.jp> Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Co-authored-by: j4tfwm6z <proj-jpntaxi@tier4.jp> Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent ae73d48 commit f3a26bc

10 files changed

+1061
-0
lines changed
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,46 @@
1+
cmake_minimum_required(VERSION 3.5)
2+
project(obstacle_collision_checker)
3+
4+
find_package(ament_cmake_auto REQUIRED)
5+
ament_auto_find_build_dependencies()
6+
7+
### Compile options
8+
if(NOT CMAKE_CXX_STANDARD)
9+
set(CMAKE_CXX_STANDARD 14)
10+
set(CMAKE_CXX_STANDARD_REQUIRED ON)
11+
set(CMAKE_CXX_EXTENSIONS OFF)
12+
endif()
13+
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
14+
add_compile_options(-Wall -Wextra -Wpedantic -Werror)
15+
endif()
16+
17+
18+
include_directories(
19+
include
20+
${PCL_INCLUDE_DIRS}
21+
${Boost_INCLUDE_DIRS}
22+
${EIGEN3_INCLUDE_DIRS}
23+
)
24+
25+
# Target
26+
## obstacle_collision_checker_node
27+
ament_auto_add_library(obstacle_collision_checker SHARED
28+
src/obstacle_collision_checker_node/obstacle_collision_checker.cpp
29+
src/obstacle_collision_checker_node/obstacle_collision_checker_node.cpp
30+
)
31+
32+
rclcpp_components_register_node(obstacle_collision_checker
33+
PLUGIN "obstacle_collision_checker::ObstacleCollisionCheckerNode"
34+
EXECUTABLE obstacle_collision_checker_node
35+
)
36+
37+
if(BUILD_TESTING)
38+
find_package(ament_lint_auto REQUIRED)
39+
ament_lint_auto_find_test_dependencies()
40+
endif()
41+
42+
ament_auto_package(
43+
INSTALL_TO_SHARE
44+
launch
45+
config
46+
)
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,86 @@
1+
# obstacle_collision_checker
2+
3+
## Purpose
4+
5+
`obstacle_collision_checker` is a module to check obstacle collision for predicted trajectory and publish diagnostic errors if collision is found.
6+
7+
## Inner-workings / Algorithms
8+
9+
### Flow chart
10+
11+
```plantuml
12+
@startuml
13+
skinparam monochrome true
14+
15+
title obstacle collision checker : update
16+
start
17+
18+
:calculate braking distance;
19+
20+
:resampling trajectory;
21+
note right
22+
to reduce calculation cost
23+
end note
24+
:filter point cloud by trajectory;
25+
26+
:create vehicle foot prints;
27+
28+
:create vehicle passing area;
29+
30+
partition will_collide {
31+
32+
while (has next ego vehicle foot print) is (yes)
33+
:found collision with obstacle foot print;
34+
if (has collision with obstacle) then (yes)
35+
:set diag to ERROR;
36+
stop
37+
endif
38+
end while (no)
39+
:set diag to OK;
40+
stop
41+
}
42+
43+
@enduml
44+
```
45+
46+
### Algorithms
47+
48+
### Check data
49+
50+
Check that `obstacle_collision_checker` receives no ground pointcloud, predicted_trajectory, reference trajectory, and current velocity data.
51+
52+
### Diagnostic update
53+
54+
If any collision is found on predicted path, this module sets `ERROR` level as diagnostic status else sets `OK`.
55+
56+
## Inputs / Outputs
57+
58+
### Input
59+
60+
| Name | Type | Description |
61+
| ---------------------------------------------- | ---------------------------------------------- | ------------------------------------------------------------------ |
62+
| `~/input/trajectory` | `autoware_auto_planning_msgs::msg::Trajectory` | Reference trajectory |
63+
| `~/input/trajectory` | `autoware_auto_planning_msgs::msg::Trajectory` | Predicted trajectory |
64+
| `/perception/obstacle_segmentation/pointcloud` | `sensor_msgs::msg::PointCloud2` | Pointcloud of obstacles which the ego-vehicle should stop or avoid |
65+
| `/tf` | `tf2_msgs::msg::TFMessage` | TF |
66+
| `/tf_static` | `tf2_msgs::msg::TFMessage` | TF static |
67+
68+
### Output
69+
70+
| Name | Type | Description |
71+
| ---------------- | -------------------------------------- | ------------------------ |
72+
| `~/debug/marker` | `visualization_msgs::msg::MarkerArray` | Marker for visualization |
73+
74+
## Parameters
75+
76+
| Name | Type | Description | Default value |
77+
| :------------------ | :------- | :------------------------------------------------- | :------------ |
78+
| `delay_time` | `double` | Delay time of vehicle [s] | 0.3 |
79+
| `footprint_margin` | `double` | Foot print margin [m] | 0.0 |
80+
| `max_deceleration` | `double` | Max deceleration for ego vehicle to stop [m/s^2] | 2.0 |
81+
| `resample_interval` | `double` | Interval for resampling trajectory [m] | 0.3 |
82+
| `search_radius` | `double` | Search distance from trajectory to point cloud [m] | 5.0 |
83+
84+
## Assumptions / Known limits
85+
86+
To perform proper collision check, it is necessary to get probably predicted trajectory and obstacle pointclouds without noise.
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,11 @@
1+
/**:
2+
ros__parameters:
3+
# Node
4+
update_rate: 10.0
5+
6+
# Core
7+
delay_time: 0.3 # delay time of vehicle [s]
8+
footprint_margin: 0.0 # margin for footprint [m]
9+
max_deceleration: 2.0 # max deceleration [m/ss]
10+
resample_interval: 0.3 # interval distance to resample point cloud [m]
11+
search_radius: 5.0 # search distance from trajectory to point cloud [m]
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,107 @@
1+
// Copyright 2020 Tier IV, Inc. All rights reserved.
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+
#ifndef OBSTACLE_COLLISION_CHECKER__OBSTACLE_COLLISION_CHECKER_HPP_
16+
#define OBSTACLE_COLLISION_CHECKER__OBSTACLE_COLLISION_CHECKER_HPP_
17+
18+
#include <autoware_utils/geometry/boost_geometry.hpp>
19+
#include <vehicle_info_util/vehicle_info_util.hpp>
20+
21+
#include <autoware_auto_planning_msgs/msg/trajectory.hpp>
22+
#include <geometry_msgs/msg/pose_stamped.hpp>
23+
#include <geometry_msgs/msg/transform_stamped.hpp>
24+
#include <geometry_msgs/msg/twist.hpp>
25+
#include <sensor_msgs/msg/point_cloud2.hpp>
26+
27+
#include <boost/optional.hpp>
28+
29+
#include <pcl/point_cloud.h>
30+
#include <pcl/point_types.h>
31+
32+
#include <map>
33+
#include <string>
34+
#include <vector>
35+
36+
namespace obstacle_collision_checker
37+
{
38+
using autoware_utils::LinearRing2d;
39+
40+
struct Param
41+
{
42+
double delay_time;
43+
double footprint_margin;
44+
double max_deceleration;
45+
double resample_interval;
46+
double search_radius;
47+
};
48+
49+
struct Input
50+
{
51+
geometry_msgs::msg::PoseStamped::ConstSharedPtr current_pose;
52+
geometry_msgs::msg::Twist::ConstSharedPtr current_twist;
53+
sensor_msgs::msg::PointCloud2::ConstSharedPtr obstacle_pointcloud;
54+
geometry_msgs::msg::TransformStamped::ConstSharedPtr obstacle_transform;
55+
autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr reference_trajectory;
56+
autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr predicted_trajectory;
57+
};
58+
59+
struct Output
60+
{
61+
std::map<std::string, double> processing_time_map;
62+
bool will_collide;
63+
autoware_auto_planning_msgs::msg::Trajectory resampled_trajectory;
64+
std::vector<LinearRing2d> vehicle_footprints;
65+
std::vector<LinearRing2d> vehicle_passing_areas;
66+
};
67+
68+
class ObstacleCollisionChecker
69+
{
70+
public:
71+
explicit ObstacleCollisionChecker(rclcpp::Node & node);
72+
Output update(const Input & input);
73+
74+
void setParam(const Param & param) { param_ = param; }
75+
76+
private:
77+
Param param_;
78+
vehicle_info_util::VehicleInfo vehicle_info_;
79+
80+
//! This function assumes the input trajectory is sampled dense enough
81+
static autoware_auto_planning_msgs::msg::Trajectory resampleTrajectory(
82+
const autoware_auto_planning_msgs::msg::Trajectory & trajectory, const double interval);
83+
84+
static autoware_auto_planning_msgs::msg::Trajectory cutTrajectory(
85+
const autoware_auto_planning_msgs::msg::Trajectory & trajectory, const double length);
86+
87+
static std::vector<LinearRing2d> createVehicleFootprints(
88+
const autoware_auto_planning_msgs::msg::Trajectory & trajectory, const Param & param,
89+
const vehicle_info_util::VehicleInfo & vehicle_info);
90+
91+
static std::vector<LinearRing2d> createVehiclePassingAreas(
92+
const std::vector<LinearRing2d> & vehicle_footprints);
93+
94+
static LinearRing2d createHullFromFootprints(
95+
const LinearRing2d & area1, const LinearRing2d & area2);
96+
97+
static bool willCollide(
98+
const pcl::PointCloud<pcl::PointXYZ> & obstacle_pointcloud,
99+
const std::vector<LinearRing2d> & vehicle_footprints);
100+
101+
static bool hasCollision(
102+
const pcl::PointCloud<pcl::PointXYZ> & obstacle_pointcloud,
103+
const LinearRing2d & vehicle_footprint);
104+
};
105+
} // namespace obstacle_collision_checker
106+
107+
#endif // OBSTACLE_COLLISION_CHECKER__OBSTACLE_COLLISION_CHECKER_HPP_
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,110 @@
1+
// Copyright 2020 Tier IV, Inc. All rights reserved.
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+
#ifndef OBSTACLE_COLLISION_CHECKER__OBSTACLE_COLLISION_CHECKER_NODE_HPP_
16+
#define OBSTACLE_COLLISION_CHECKER__OBSTACLE_COLLISION_CHECKER_NODE_HPP_
17+
18+
#include "obstacle_collision_checker/obstacle_collision_checker.hpp"
19+
20+
#include <autoware_utils/geometry/geometry.hpp>
21+
#include <autoware_utils/ros/debug_publisher.hpp>
22+
#include <autoware_utils/ros/processing_time_publisher.hpp>
23+
#include <autoware_utils/ros/self_pose_listener.hpp>
24+
#include <autoware_utils/ros/transform_listener.hpp>
25+
#include <diagnostic_updater/diagnostic_updater.hpp>
26+
#include <rclcpp/rclcpp.hpp>
27+
28+
#include <autoware_auto_planning_msgs/msg/trajectory.hpp>
29+
#include <geometry_msgs/msg/pose_stamped.hpp>
30+
#include <nav_msgs/msg/odometry.hpp>
31+
#include <sensor_msgs/msg/point_cloud2.hpp>
32+
#include <visualization_msgs/msg/marker_array.hpp>
33+
34+
#include <memory>
35+
#include <vector>
36+
37+
namespace obstacle_collision_checker
38+
{
39+
struct NodeParam
40+
{
41+
double update_rate;
42+
};
43+
44+
class ObstacleCollisionCheckerNode : public rclcpp::Node
45+
{
46+
public:
47+
explicit ObstacleCollisionCheckerNode(const rclcpp::NodeOptions & node_options);
48+
49+
private:
50+
// Subscriber
51+
std::shared_ptr<autoware_utils::SelfPoseListener> self_pose_listener_;
52+
std::shared_ptr<autoware_utils::TransformListener> transform_listener_;
53+
rclcpp::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr sub_obstacle_pointcloud_;
54+
rclcpp::Subscription<autoware_auto_planning_msgs::msg::Trajectory>::SharedPtr
55+
sub_reference_trajectory_;
56+
rclcpp::Subscription<autoware_auto_planning_msgs::msg::Trajectory>::SharedPtr
57+
sub_predicted_trajectory_;
58+
rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr sub_odom_;
59+
60+
// Data Buffer
61+
geometry_msgs::msg::PoseStamped::ConstSharedPtr current_pose_;
62+
geometry_msgs::msg::Twist::ConstSharedPtr current_twist_;
63+
sensor_msgs::msg::PointCloud2::ConstSharedPtr obstacle_pointcloud_;
64+
geometry_msgs::msg::TransformStamped::ConstSharedPtr obstacle_transform_;
65+
autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr reference_trajectory_;
66+
autoware_auto_planning_msgs::msg::Trajectory::ConstSharedPtr predicted_trajectory_;
67+
68+
// Callback
69+
void onObstaclePointcloud(const sensor_msgs::msg::PointCloud2::SharedPtr msg);
70+
void onReferenceTrajectory(const autoware_auto_planning_msgs::msg::Trajectory::SharedPtr msg);
71+
void onPredictedTrajectory(const autoware_auto_planning_msgs::msg::Trajectory::SharedPtr msg);
72+
void onOdom(const nav_msgs::msg::Odometry::SharedPtr msg);
73+
74+
// Publisher
75+
std::shared_ptr<autoware_utils::DebugPublisher> debug_publisher_;
76+
std::shared_ptr<autoware_utils::ProcessingTimePublisher> time_publisher_;
77+
78+
// Timer
79+
rclcpp::TimerBase::SharedPtr timer_;
80+
void initTimer(double period_s);
81+
82+
bool isDataReady();
83+
bool isDataTimeout();
84+
void onTimer();
85+
86+
// Parameter
87+
NodeParam node_param_;
88+
Param param_;
89+
90+
// Dynamic Reconfigure
91+
OnSetParametersCallbackHandle::SharedPtr set_param_res_;
92+
rcl_interfaces::msg::SetParametersResult paramCallback(
93+
const std::vector<rclcpp::Parameter> & parameters);
94+
95+
// Core
96+
Input input_;
97+
Output output_;
98+
std::unique_ptr<ObstacleCollisionChecker> obstacle_collision_checker_;
99+
100+
// Diagnostic Updater
101+
diagnostic_updater::Updater updater_;
102+
103+
void checkLaneDeparture(diagnostic_updater::DiagnosticStatusWrapper & stat);
104+
105+
// Visualization
106+
visualization_msgs::msg::MarkerArray createMarkerArray() const;
107+
};
108+
} // namespace obstacle_collision_checker
109+
110+
#endif // OBSTACLE_COLLISION_CHECKER__OBSTACLE_COLLISION_CHECKER_NODE_HPP_

0 commit comments

Comments
 (0)