Skip to content

Commit d86c46a

Browse files
authored
feat(motion_velocity_planner): introduce Object/Pointcloud structure in PlannerData (#9812)
* feat: new object/pointcloud struct in motion velocity planner Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * update planner_data Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * modify modules Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> * fix Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com> --------- Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
1 parent ca2d4e7 commit d86c46a

File tree

13 files changed

+121
-44
lines changed

13 files changed

+121
-44
lines changed

planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/dynamic_obstacle_stop_module.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -131,7 +131,7 @@ VelocityPlanningResult DynamicObstacleStopModule::plan(
131131
? 0.0
132132
: params_.hysteresis;
133133
const auto dynamic_obstacles = dynamic_obstacle_stop::filter_predicted_objects(
134-
planner_data->predicted_objects, ego_data, params_, hysteresis);
134+
planner_data->objects, ego_data, params_, hysteresis);
135135

136136
const auto preprocessing_duration_us = stopwatch.toc("preprocessing");
137137

planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/object_filtering.cpp

+11-9
Original file line numberDiff line numberDiff line change
@@ -96,20 +96,22 @@ bool is_unavoidable(
9696
};
9797

9898
std::vector<autoware_perception_msgs::msg::PredictedObject> filter_predicted_objects(
99-
const autoware_perception_msgs::msg::PredictedObjects & objects, const EgoData & ego_data,
99+
const std::vector<PlannerData::Object> & objects, const EgoData & ego_data,
100100
const PlannerParam & params, const double hysteresis)
101101
{
102102
std::vector<autoware_perception_msgs::msg::PredictedObject> filtered_objects;
103-
for (const auto & object : objects.objects) {
104-
const auto is_not_too_slow = object.kinematics.initial_twist_with_covariance.twist.linear.x >=
105-
params.minimum_object_velocity;
103+
for (const auto & object : objects) {
104+
const auto & predicted_object = object.predicted_object;
105+
const auto is_not_too_slow =
106+
predicted_object.kinematics.initial_twist_with_covariance.twist.linear.x >=
107+
params.minimum_object_velocity;
106108
if (
107-
is_vehicle(object) && is_not_too_slow &&
108-
is_in_range(object, ego_data.trajectory, params, hysteresis) &&
109-
is_not_too_close(object, ego_data, params.ego_longitudinal_offset) &&
109+
is_vehicle(predicted_object) && is_not_too_slow &&
110+
is_in_range(predicted_object, ego_data.trajectory, params, hysteresis) &&
111+
is_not_too_close(predicted_object, ego_data, params.ego_longitudinal_offset) &&
110112
(!params.ignore_unavoidable_collisions ||
111-
!is_unavoidable(object, ego_data.pose, ego_data.earliest_stop_pose, params)))
112-
filtered_objects.push_back(object);
113+
!is_unavoidable(predicted_object, ego_data.pose, ego_data.earliest_stop_pose, params)))
114+
filtered_objects.push_back(predicted_object);
113115
}
114116
return filtered_objects;
115117
}

planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/src/object_filtering.hpp

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

1818
#include "types.hpp"
1919

20+
#include <autoware/motion_velocity_planner_common/planner_data.hpp>
21+
2022
#include <autoware_perception_msgs/msg/predicted_objects.hpp>
2123

2224
#include <vector>
@@ -74,7 +76,7 @@ bool is_unavoidable(
7476
/// @param hysteresis [m] extra distance threshold used for filtering
7577
/// @return filtered predicted objects
7678
std::vector<autoware_perception_msgs::msg::PredictedObject> filter_predicted_objects(
77-
const autoware_perception_msgs::msg::PredictedObjects & objects, const EgoData & ego_data,
79+
const std::vector<PlannerData::Object> & objects, const EgoData & ego_data,
7880
const PlannerParam & params, const double hysteresis);
7981

8082
} // namespace autoware::motion_velocity_planner::dynamic_obstacle_stop

planning/motion_velocity_planner/autoware_motion_velocity_dynamic_obstacle_stop_module/test/test_object_filtering.cpp

+4-2
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,7 @@
1414

1515
#include "../src/object_filtering.hpp"
1616

17+
#include <autoware/motion_velocity_planner_common/planner_data.hpp>
1718
#include <autoware/universe_utils/geometry/geometry.hpp>
1819

1920
#include <autoware_perception_msgs/msg/detail/object_classification__struct.hpp>
@@ -26,6 +27,8 @@
2627
#include <gtest/gtest.h>
2728
#include <lanelet2_core/geometry/LineString.h>
2829

30+
#include <vector>
31+
2932
TEST(TestObjectFiltering, isVehicle)
3033
{
3134
using autoware::motion_velocity_planner::dynamic_obstacle_stop::is_vehicle;
@@ -202,8 +205,7 @@ TEST(TestObjectFiltering, isUnavoidable)
202205
TEST(TestObjectFiltering, filterPredictedObjects)
203206
{
204207
using autoware::motion_velocity_planner::dynamic_obstacle_stop::filter_predicted_objects;
205-
autoware_perception_msgs::msg::PredictedObjects objects;
206-
autoware_perception_msgs::msg::PredictedObject object;
208+
std::vector<autoware::motion_velocity_planner::PlannerData::Object> objects;
207209
autoware::motion_velocity_planner::dynamic_obstacle_stop::EgoData ego_data;
208210
autoware::motion_velocity_planner::dynamic_obstacle_stop::PlannerParam params;
209211
double hysteresis{};

planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@ namespace autoware::motion_velocity_planner::obstacle_velocity_limiter
2929
{
3030

3131
multi_polygon_t createPolygonMasks(
32-
const autoware_perception_msgs::msg::PredictedObjects & dynamic_obstacles, const double buffer,
32+
const std::vector<PlannerData::Object> & dynamic_obstacles, const double buffer,
3333
const double min_vel)
3434
{
3535
return createObjectPolygons(dynamic_obstacles, buffer, min_vel);

planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -56,7 +56,7 @@ void calculateSteeringAngles(TrajectoryPoints & trajectory, const double wheel_b
5656
/// @param[in] min_vel minimum velocity for an object to be masked
5757
/// @return polygon masks around dynamic objects
5858
multi_polygon_t createPolygonMasks(
59-
const autoware_perception_msgs::msg::PredictedObjects & dynamic_obstacles, const double buffer,
59+
const std::vector<PlannerData::Object> & dynamic_obstacles, const double buffer,
6060
const double min_vel);
6161

6262
/// @brief create footprint polygons from projection lines

planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacle_velocity_limiter_module.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -170,7 +170,7 @@ VelocityPlanningResult ObstacleVelocityLimiterModule::plan(
170170
const auto preprocessing_us = stopwatch.toc("preprocessing");
171171
stopwatch.tic("obstacles");
172172
obstacle_masks.negative_masks = obstacle_velocity_limiter::createPolygonMasks(
173-
planner_data->predicted_objects, obstacle_params_.dynamic_obstacles_buffer,
173+
planner_data->objects, obstacle_params_.dynamic_obstacles_buffer,
174174
obstacle_params_.dynamic_obstacles_min_vel);
175175
if (obstacle_params_.ignore_on_path)
176176
obstacle_masks.negative_masks.push_back(obstacle_velocity_limiter::createTrajectoryFootprint(
@@ -189,8 +189,8 @@ VelocityPlanningResult ObstacleVelocityLimiterModule::plan(
189189
obstacle_masks.positive_mask =
190190
obstacle_velocity_limiter::createEnvelopePolygon(footprint_polygons);
191191
obstacle_velocity_limiter::addSensorObstacles(
192-
obstacles, planner_data->occupancy_grid, planner_data->no_ground_pointcloud, obstacle_masks,
193-
obstacle_params_);
192+
obstacles, planner_data->occupancy_grid, planner_data->no_ground_pointcloud.pointcloud,
193+
obstacle_masks, obstacle_params_);
194194
}
195195
const auto obstacles_us = stopwatch.toc("obstacles");
196196
autoware::motion_utils::VirtualWalls virtual_walls;

planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacles.cpp

+8-6
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,7 @@
2525
#include <tf2/utils.h>
2626

2727
#include <algorithm>
28+
#include <vector>
2829

2930
namespace autoware::motion_velocity_planner::obstacle_velocity_limiter
3031
{
@@ -58,17 +59,18 @@ polygon_t createObjectPolygon(
5859
}
5960

6061
multi_polygon_t createObjectPolygons(
61-
const autoware_perception_msgs::msg::PredictedObjects & objects, const double buffer,
62-
const double min_velocity)
62+
const std::vector<PlannerData::Object> & objects, const double buffer, const double min_velocity)
6363
{
6464
multi_polygon_t polygons;
65-
for (const auto & object : objects.objects) {
65+
for (const auto & object : objects) {
66+
const auto & predicted_object = object.predicted_object;
6667
const double obj_vel_norm = std::hypot(
67-
object.kinematics.initial_twist_with_covariance.twist.linear.x,
68-
object.kinematics.initial_twist_with_covariance.twist.linear.y);
68+
predicted_object.kinematics.initial_twist_with_covariance.twist.linear.x,
69+
predicted_object.kinematics.initial_twist_with_covariance.twist.linear.y);
6970
if (min_velocity <= obj_vel_norm) {
7071
polygons.push_back(createObjectPolygon(
71-
object.kinematics.initial_pose_with_covariance.pose, object.shape.dimensions, buffer));
72+
predicted_object.kinematics.initial_pose_with_covariance.pose,
73+
predicted_object.shape.dimensions, buffer));
7274
}
7375
}
7476
return polygons;

planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/src/obstacles.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
#include "parameters.hpp"
1919
#include "types.hpp"
2020

21+
#include <autoware/motion_velocity_planner_common/planner_data.hpp>
2122
#include <autoware/universe_utils/ros/transform_listener.hpp>
2223

2324
#include <autoware_perception_msgs/msg/predicted_objects.hpp>
@@ -163,8 +164,7 @@ polygon_t createObjectPolygon(
163164
/// @param [in] min_velocity objects with velocity lower will be ignored
164165
/// @return polygons of the objects
165166
multi_polygon_t createObjectPolygons(
166-
const autoware_perception_msgs::msg::PredictedObjects & objects, const double buffer,
167-
const double min_velocity);
167+
const std::vector<PlannerData::Object> & objects, const double buffer, const double min_velocity);
168168

169169
/// @brief add obstacles obtained from sensors to the given Obstacles object
170170
/// @param[out] obstacles Obstacles object in which to add the sensor obstacles

planning/motion_velocity_planner/autoware_motion_velocity_obstacle_velocity_limiter_module/test/test_collision_distance.cpp

+6-3
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
#include "../src/distance.hpp"
1616
#include "../src/obstacles.hpp"
1717
#include "../src/types.hpp"
18+
#include "autoware/motion_velocity_planner_common/planner_data.hpp"
1819
#include "autoware/universe_utils/geometry/geometry.hpp"
1920

2021
#include <autoware_perception_msgs/msg/predicted_object.hpp>
@@ -27,6 +28,7 @@
2728

2829
#include <algorithm>
2930
#include <limits>
31+
#include <vector>
3032

3133
const auto point_in_polygon = [](const auto x, const auto y, const auto & polygon) {
3234
return std::find_if(polygon.outer().begin(), polygon.outer().end(), [=](const auto & pt) {
@@ -387,11 +389,12 @@ TEST(TestCollisionDistance, arcDistance)
387389

388390
TEST(TestCollisionDistance, createObjPolygons)
389391
{
392+
using autoware::motion_velocity_planner::PlannerData;
390393
using autoware::motion_velocity_planner::obstacle_velocity_limiter::createObjectPolygons;
391394
using autoware_perception_msgs::msg::PredictedObject;
392395
using autoware_perception_msgs::msg::PredictedObjects;
393396

394-
PredictedObjects objects;
397+
std::vector<PlannerData::Object> objects;
395398

396399
auto polygons = createObjectPolygons(objects, 0.0, 0.0);
397400
EXPECT_TRUE(polygons.empty());
@@ -404,7 +407,7 @@ TEST(TestCollisionDistance, createObjPolygons)
404407
object1.kinematics.initial_twist_with_covariance.twist.linear.x = 0.0;
405408
object1.shape.dimensions.x = 1.0;
406409
object1.shape.dimensions.y = 1.0;
407-
objects.objects.push_back(object1);
410+
objects.push_back(PlannerData::Object(object1));
408411

409412
polygons = createObjectPolygons(objects, 0.0, 1.0);
410413
EXPECT_TRUE(polygons.empty());
@@ -431,7 +434,7 @@ TEST(TestCollisionDistance, createObjPolygons)
431434
object2.kinematics.initial_twist_with_covariance.twist.linear.x = 2.0;
432435
object2.shape.dimensions.x = 2.0;
433436
object2.shape.dimensions.y = 1.0;
434-
objects.objects.push_back(object2);
437+
objects.push_back(PlannerData::Object(object2));
435438

436439
polygons = createObjectPolygons(objects, 0.0, 2.0);
437440
ASSERT_EQ(polygons.size(), 1ul);

planning/motion_velocity_planner/autoware_motion_velocity_out_of_lane_module/src/filter_predicted_objects.cpp

+14-11
Original file line numberDiff line numberDiff line change
@@ -106,34 +106,37 @@ autoware_perception_msgs::msg::PredictedObjects filter_predicted_objects(
106106
const PlannerData & planner_data, const EgoData & ego_data, const PlannerParam & params)
107107
{
108108
autoware_perception_msgs::msg::PredictedObjects filtered_objects;
109-
filtered_objects.header = planner_data.predicted_objects.header;
110-
for (const auto & object : planner_data.predicted_objects.objects) {
109+
filtered_objects.header = planner_data.predicted_objects_header;
110+
for (const auto & object : planner_data.objects) {
111+
const auto & predicted_object = object.predicted_object;
111112
const auto is_pedestrian =
112-
std::find_if(object.classification.begin(), object.classification.end(), [](const auto & c) {
113-
return c.label == autoware_perception_msgs::msg::ObjectClassification::PEDESTRIAN;
114-
}) != object.classification.end();
113+
std::find_if(
114+
predicted_object.classification.begin(), predicted_object.classification.end(),
115+
[](const auto & c) {
116+
return c.label == autoware_perception_msgs::msg::ObjectClassification::PEDESTRIAN;
117+
}) != predicted_object.classification.end();
115118
if (is_pedestrian) continue;
116119

117120
const auto is_coming_from_behind =
118121
motion_utils::calcSignedArcLength(
119122
ego_data.trajectory_points, 0UL,
120-
object.kinematics.initial_pose_with_covariance.pose.position) < 0.0;
123+
predicted_object.kinematics.initial_pose_with_covariance.pose.position) < 0.0;
121124
if (params.objects_ignore_behind_ego && is_coming_from_behind) {
122125
continue;
123126
}
124127

125-
auto filtered_object = object;
128+
auto filtered_object = predicted_object;
126129
const auto is_invalid_predicted_path = [&](const auto & predicted_path) {
127130
const auto is_low_confidence = predicted_path.confidence < params.objects_min_confidence;
128131
const auto no_overlap_path = motion_utils::removeOverlapPoints(predicted_path.path);
129132
if (no_overlap_path.size() <= 1) return true;
130133
const auto lat_offset_to_current_ego =
131134
std::abs(motion_utils::calcLateralOffset(no_overlap_path, ego_data.pose.position));
132135
const auto is_crossing_ego =
133-
lat_offset_to_current_ego <=
134-
object.shape.dimensions.y / 2.0 + std::max(
135-
params.left_offset + params.extra_left_offset,
136-
params.right_offset + params.extra_right_offset);
136+
lat_offset_to_current_ego <= predicted_object.shape.dimensions.y / 2.0 +
137+
std::max(
138+
params.left_offset + params.extra_left_offset,
139+
params.right_offset + params.extra_right_offset);
137140
return is_low_confidence || is_crossing_ego;
138141
};
139142
auto & predicted_paths = filtered_object.kinematics.predicted_paths;

planning/motion_velocity_planner/autoware_motion_velocity_planner_common/include/autoware/motion_velocity_planner_common/planner_data.hpp

+64-2
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,7 @@
3939
#include <map>
4040
#include <memory>
4141
#include <optional>
42+
#include <vector>
4243

4344
namespace autoware::motion_velocity_planner
4445
{
@@ -54,11 +55,72 @@ struct PlannerData
5455
{
5556
}
5657

58+
struct Object
59+
{
60+
public:
61+
Object() = default;
62+
explicit Object(const autoware_perception_msgs::msg::PredictedObject & arg_predicted_object)
63+
: predicted_object(arg_predicted_object)
64+
{
65+
}
66+
67+
autoware_perception_msgs::msg::PredictedObject predicted_object;
68+
// double get_lon_vel_relative_to_traj()
69+
// {
70+
// if (!lon_vel_relative_to_traj) {
71+
// lon_vel_relative_to_traj = 0.0;
72+
// }
73+
// return *lon_vel_relative_to_traj;
74+
// }
75+
// double get_lat_vel_relative_to_traj()
76+
// {
77+
// if (!lat_vel_relative_to_traj) {
78+
// lat_vel_relative_to_traj = 0.0;
79+
// }
80+
// return *lat_vel_relative_to_traj;
81+
// }
82+
83+
private:
84+
// TODO(murooka) implement the following variables and their functions.
85+
// std::optional<double> dist_to_traj_poly{std::nullopt};
86+
// std::optional<double> dist_to_traj_lateral{std::nullopt};
87+
// std::optional<double> dist_from_ego_longitudinal{std::nullopt};
88+
// std::optional<double> lon_vel_relative_to_traj{std::nullopt};
89+
// std::optional<double> lat_vel_relative_to_traj{std::nullopt};
90+
};
91+
92+
struct Pointcloud
93+
{
94+
public:
95+
Pointcloud() = default;
96+
explicit Pointcloud(const pcl::PointCloud<pcl::PointXYZ> & arg_pointcloud)
97+
: pointcloud(arg_pointcloud)
98+
{
99+
}
100+
101+
pcl::PointCloud<pcl::PointXYZ> pointcloud;
102+
103+
private:
104+
// NOTE: clustered result will be added.
105+
};
106+
107+
void process_predicted_objects(
108+
const autoware_perception_msgs::msg::PredictedObjects & predicted_objects)
109+
{
110+
predicted_objects_header = predicted_objects.header;
111+
112+
objects.clear();
113+
for (const auto & predicted_object : predicted_objects.objects) {
114+
objects.push_back(Object(predicted_object));
115+
}
116+
}
117+
57118
// msgs from callbacks that are used for data-ready
58119
nav_msgs::msg::Odometry current_odometry;
59120
geometry_msgs::msg::AccelWithCovarianceStamped current_acceleration;
60-
autoware_perception_msgs::msg::PredictedObjects predicted_objects;
61-
pcl::PointCloud<pcl::PointXYZ> no_ground_pointcloud;
121+
std_msgs::msg::Header predicted_objects_header;
122+
std::vector<Object> objects;
123+
Pointcloud no_ground_pointcloud;
62124
nav_msgs::msg::OccupancyGrid occupancy_grid;
63125
std::shared_ptr<route_handler::RouteHandler> route_handler;
64126

planning/motion_velocity_planner/autoware_motion_velocity_planner_node/src/node.cpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -161,13 +161,14 @@ bool MotionVelocityPlannerNode::update_planner_data(
161161

162162
const auto predicted_objects_ptr = sub_predicted_objects_.takeData();
163163
if (check_with_log(predicted_objects_ptr, "Waiting for predicted objects"))
164-
planner_data_.predicted_objects = *predicted_objects_ptr;
164+
planner_data_.process_predicted_objects(*predicted_objects_ptr);
165165
processing_times["update_planner_data.pred_obj"] = sw.toc(true);
166166

167167
const auto no_ground_pointcloud_ptr = sub_no_ground_pointcloud_.takeData();
168168
if (check_with_log(no_ground_pointcloud_ptr, "Waiting for pointcloud")) {
169169
const auto no_ground_pointcloud = process_no_ground_pointcloud(no_ground_pointcloud_ptr);
170-
if (no_ground_pointcloud) planner_data_.no_ground_pointcloud = *no_ground_pointcloud;
170+
if (no_ground_pointcloud)
171+
planner_data_.no_ground_pointcloud = PlannerData::Pointcloud(*no_ground_pointcloud);
171172
}
172173
processing_times["update_planner_data.pcd"] = sw.toc(true);
173174

0 commit comments

Comments
 (0)