Skip to content

Commit 67ab350

Browse files
authored
feat(behavior_velocity_planner)!: remove velocity_factor completely (#9943)
* feat(behavior_velocity_planner)!: remove velocity_factor completely Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp> * minimize diff Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp> --------- Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
1 parent 0bf689c commit 67ab350

File tree

12 files changed

+39
-92
lines changed

12 files changed

+39
-92
lines changed

planning/behavior_velocity_planner/autoware_behavior_velocity_detection_area_module/src/scene.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -46,7 +46,6 @@ DetectionAreaModule::DetectionAreaModule(
4646
planner_param_(planner_param),
4747
debug_data_()
4848
{
49-
velocity_factor_.init(PlanningBehavior::USER_DEFINED_DETECTION_AREA);
5049
}
5150

5251
bool DetectionAreaModule::modifyPathVelocity(PathWithLaneId * path)
@@ -180,9 +179,10 @@ bool DetectionAreaModule::modifyPathVelocity(PathWithLaneId * path)
180179

181180
// Create StopReason
182181
{
183-
velocity_factor_.set(
184-
path->points, planner_data_->current_odometry->pose, stop_point->second,
185-
VelocityFactor::UNKNOWN);
182+
planning_factor_interface_->add(
183+
path->points, planner_data_->current_odometry->pose, stop_pose, stop_pose,
184+
tier4_planning_msgs::msg::PlanningFactor::STOP, tier4_planning_msgs::msg::SafetyFactorArray{},
185+
true /*is_driving_forward*/, 0.0, 0.0 /*shift distance*/, "");
186186
}
187187

188188
return true;

planning/behavior_velocity_planner/autoware_behavior_velocity_intersection_module/src/scene_intersection.cpp

-2
Original file line numberDiff line numberDiff line change
@@ -44,8 +44,6 @@ namespace autoware::behavior_velocity_planner
4444
{
4545
namespace bg = boost::geometry;
4646

47-
using autoware::motion_utils::VelocityFactorInterface;
48-
4947
IntersectionModule::IntersectionModule(
5048
const int64_t module_id, const int64_t lane_id,
5149
[[maybe_unused]] std::shared_ptr<const PlannerData> planner_data,

planning/behavior_velocity_planner/autoware_behavior_velocity_no_drivable_lane_module/src/scene.cpp

+12-7
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,6 @@ NoDrivableLaneModule::NoDrivableLaneModule(
3838
debug_data_(),
3939
state_(State::INIT)
4040
{
41-
velocity_factor_.init(PlanningBehavior::NO_DRIVABLE_LANE);
4241
}
4342

4443
bool NoDrivableLaneModule::modifyPathVelocity(PathWithLaneId * path)
@@ -166,8 +165,10 @@ void NoDrivableLaneModule::handle_approaching_state(PathWithLaneId * path)
166165
// Get stop point and stop factor
167166
{
168167
const auto & stop_pose = op_stop_pose.value();
169-
velocity_factor_.set(
170-
path->points, planner_data_->current_odometry->pose, stop_pose, VelocityFactor::APPROACHING);
168+
planning_factor_interface_->add(
169+
path->points, planner_data_->current_odometry->pose, stop_pose, stop_pose,
170+
tier4_planning_msgs::msg::PlanningFactor::STOP, tier4_planning_msgs::msg::SafetyFactorArray{},
171+
true /*is_driving_forward*/, 0.0, 0.0 /*shift distance*/, "");
171172

172173
const auto virtual_wall_pose = autoware::motion_utils::calcLongitudinalOffsetPose(
173174
path->points, stop_pose.position, debug_data_.base_link2front);
@@ -214,8 +215,10 @@ void NoDrivableLaneModule::handle_inside_no_drivable_lane_state(PathWithLaneId *
214215
// Get stop point and stop factor
215216
{
216217
const auto & stop_pose = autoware::universe_utils::getPose(path->points.at(0));
217-
velocity_factor_.set(
218-
path->points, planner_data_->current_odometry->pose, stop_pose, VelocityFactor::APPROACHING);
218+
planning_factor_interface_->add(
219+
path->points, planner_data_->current_odometry->pose, stop_pose, stop_pose,
220+
tier4_planning_msgs::msg::PlanningFactor::STOP, tier4_planning_msgs::msg::SafetyFactorArray{},
221+
true /*is_driving_forward*/, 0.0, 0.0 /*shift distance*/, "");
219222

220223
const auto & virtual_wall_pose = autoware::motion_utils::calcLongitudinalOffsetPose(
221224
path->points, stop_pose.position, debug_data_.base_link2front);
@@ -252,8 +255,10 @@ void NoDrivableLaneModule::handle_stopped_state(PathWithLaneId * path)
252255
// Get stop point and stop factor
253256
{
254257
const auto & stop_pose = ego_pos_on_path.pose;
255-
velocity_factor_.set(
256-
path->points, planner_data_->current_odometry->pose, stop_pose, VelocityFactor::STOPPED);
258+
planning_factor_interface_->add(
259+
path->points, planner_data_->current_odometry->pose, stop_pose, stop_pose,
260+
tier4_planning_msgs::msg::PlanningFactor::STOP, tier4_planning_msgs::msg::SafetyFactorArray{},
261+
true /*is_driving_forward*/, 0.0, 0.0 /*shift distance*/, "");
257262

258263
const auto virtual_wall_pose = autoware::motion_utils::calcLongitudinalOffsetPose(
259264
path->points, stop_pose.position, debug_data_.base_link2front);

planning/behavior_velocity_planner/autoware_behavior_velocity_no_stopping_area_module/src/scene_no_stopping_area.cpp

+5-4
Original file line numberDiff line numberDiff line change
@@ -50,7 +50,6 @@ NoStoppingAreaModule::NoStoppingAreaModule(
5050
planner_param_(planner_param),
5151
debug_data_()
5252
{
53-
velocity_factor_.init(PlanningBehavior::NO_STOPPING_AREA);
5453
state_machine_.setState(StateMachine::State::GO);
5554
state_machine_.setMarginTime(planner_param_.state_clear_time);
5655
}
@@ -144,9 +143,11 @@ bool NoStoppingAreaModule::modifyPathVelocity(PathWithLaneId * path)
144143

145144
// Create StopReason
146145
{
147-
velocity_factor_.set(
148-
path->points, planner_data_->current_odometry->pose, stop_point->second,
149-
VelocityFactor::UNKNOWN);
146+
planning_factor_interface_->add(
147+
path->points, planner_data_->current_odometry->pose, stop_point->second, stop_point->second,
148+
tier4_planning_msgs::msg::PlanningFactor::STOP,
149+
tier4_planning_msgs::msg::SafetyFactorArray{}, true /*is_driving_forward*/, 0.0,
150+
0.0 /*shift distance*/, "");
150151
}
151152

152153
} else if (state_machine_.getState() == StateMachine::State::GO) {

planning/behavior_velocity_planner/autoware_behavior_velocity_occlusion_spot_module/src/scene_occlusion_spot.cpp

-2
Original file line numberDiff line numberDiff line change
@@ -70,8 +70,6 @@ OcclusionSpotModule::OcclusionSpotModule(
7070
: SceneModuleInterface(module_id, logger, clock, time_keeper, planning_factor_interface),
7171
param_(planner_param)
7272
{
73-
velocity_factor_.init(PlanningBehavior::UNKNOWN);
74-
7573
if (param_.detection_method == utils::DETECTION_METHOD::OCCUPANCY_GRID) {
7674
debug_data_.detection_type = "occupancy";
7775
//! occupancy grid limitation( 100 * 100 )

planning/behavior_velocity_planner/autoware_behavior_velocity_planner_common/include/autoware/behavior_velocity_planner_common/scene_module_interface.hpp

-22
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,6 @@
1818
#include <autoware/behavior_velocity_planner_common/planner_data.hpp>
1919
#include <autoware/behavior_velocity_planner_common/utilization/util.hpp>
2020
#include <autoware/motion_utils/factor/planning_factor_interface.hpp>
21-
#include <autoware/motion_utils/factor/velocity_factor_interface.hpp>
2221
#include <autoware/motion_utils/marker/virtual_wall_marker_creator.hpp>
2322
#include <autoware/motion_utils/trajectory/trajectory.hpp>
2423
#include <autoware/objects_of_interest_marker_interface/objects_of_interest_marker_interface.hpp>
@@ -28,8 +27,6 @@
2827
#include <autoware/universe_utils/system/time_keeper.hpp>
2928
#include <builtin_interfaces/msg/time.hpp>
3029

31-
#include <autoware_adapi_v1_msgs/msg/velocity_factor.hpp>
32-
#include <autoware_adapi_v1_msgs/msg/velocity_factor_array.hpp>
3330
#include <autoware_internal_debug_msgs/msg/float64_stamped.hpp>
3431
#include <autoware_planning_msgs/msg/path.hpp>
3532
#include <tier4_planning_msgs/msg/path_with_lane_id.hpp>
@@ -51,8 +48,6 @@
5148
namespace autoware::behavior_velocity_planner
5249
{
5350

54-
using autoware::motion_utils::PlanningBehavior;
55-
using autoware::motion_utils::VelocityFactor;
5651
using autoware::objects_of_interest_marker_interface::ColorName;
5752
using autoware::objects_of_interest_marker_interface::ObjectsOfInterestMarkerInterface;
5853
using autoware::universe_utils::DebugPublisher;
@@ -97,8 +92,6 @@ class SceneModuleInterface
9792
planner_data_ = planner_data;
9893
}
9994

100-
void resetVelocityFactor() { velocity_factor_.reset(); }
101-
VelocityFactor getVelocityFactor() const { return velocity_factor_.get(); }
10295
std::vector<ObjectOfInterest> getObjectsOfInterestData() const { return objects_of_interest_; }
10396
void clearObjectsOfInterestData() { objects_of_interest_.clear(); }
10497

@@ -107,7 +100,6 @@ class SceneModuleInterface
107100
rclcpp::Logger logger_;
108101
rclcpp::Clock::SharedPtr clock_;
109102
std::shared_ptr<const PlannerData> planner_data_;
110-
autoware::motion_utils::VelocityFactorInterface velocity_factor_; // TODO(soblin): remove this
111103
std::vector<ObjectOfInterest> objects_of_interest_;
112104
mutable std::shared_ptr<universe_utils::TimeKeeper> time_keeper_;
113105
std::shared_ptr<motion_utils::PlanningFactorInterface> planning_factor_interface_;
@@ -143,8 +135,6 @@ class SceneModuleManagerInterface
143135
}
144136
pub_virtual_wall_ = node.create_publisher<visualization_msgs::msg::MarkerArray>(
145137
std::string("~/virtual_wall/") + module_name, 5);
146-
pub_velocity_factor_ = node.create_publisher<autoware_adapi_v1_msgs::msg::VelocityFactorArray>(
147-
std::string("/planning/velocity_factors/") + module_name, 1);
148138
planning_factor_interface_ =
149139
std::make_shared<motion_utils::PlanningFactorInterface>(&node, module_name);
150140

@@ -180,21 +170,12 @@ class SceneModuleManagerInterface
180170
StopWatch<std::chrono::milliseconds> stop_watch;
181171
stop_watch.tic("Total");
182172
visualization_msgs::msg::MarkerArray debug_marker_array;
183-
autoware_adapi_v1_msgs::msg::VelocityFactorArray velocity_factor_array;
184-
velocity_factor_array.header.frame_id = "map";
185-
velocity_factor_array.header.stamp = clock_->now();
186173

187174
for (const auto & scene_module : scene_modules_) {
188-
scene_module->resetVelocityFactor();
189175
scene_module->setPlannerData(planner_data_);
190176
scene_module->modifyPathVelocity(path);
191177

192178
// The velocity factor must be called after modifyPathVelocity.
193-
// TODO(soblin): remove this
194-
const auto velocity_factor = scene_module->getVelocityFactor();
195-
if (velocity_factor.behavior != PlanningBehavior::UNKNOWN) {
196-
velocity_factor_array.factors.emplace_back(velocity_factor);
197-
}
198179

199180
for (const auto & marker : scene_module->createDebugMarkerArray().markers) {
200181
debug_marker_array.markers.push_back(marker);
@@ -203,7 +184,6 @@ class SceneModuleManagerInterface
203184
virtual_wall_marker_creator_.add_virtual_walls(scene_module->createVirtualWalls());
204185
}
205186

206-
pub_velocity_factor_->publish(velocity_factor_array);
207187
planning_factor_interface_->publish();
208188
pub_debug_->publish(debug_marker_array);
209189
if (is_publish_debug_path_) {
@@ -274,8 +254,6 @@ class SceneModuleManagerInterface
274254
rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr pub_virtual_wall_;
275255
rclcpp::Publisher<visualization_msgs::msg::MarkerArray>::SharedPtr pub_debug_;
276256
rclcpp::Publisher<tier4_planning_msgs::msg::PathWithLaneId>::SharedPtr pub_debug_path_;
277-
rclcpp::Publisher<autoware_adapi_v1_msgs::msg::VelocityFactorArray>::SharedPtr
278-
pub_velocity_factor_;
279257

280258
std::shared_ptr<DebugPublisher> processing_time_publisher_;
281259

planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.cpp

+6-20
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,6 @@ StopLineModule::StopLineModule(
3838
state_(State::APPROACH),
3939
debug_data_()
4040
{
41-
velocity_factor_.init(PlanningBehavior::STOP_SIGN);
4241
}
4342

4443
bool StopLineModule::modifyPathVelocity(PathWithLaneId * path)
@@ -62,7 +61,12 @@ bool StopLineModule::modifyPathVelocity(PathWithLaneId * path)
6261

6362
path->points = trajectory->restore();
6463

65-
updateVelocityFactor(&velocity_factor_, state_, *stop_point - ego_s);
64+
// TODO(soblin): PlanningFactorInterface use trajectory class
65+
planning_factor_interface_->add(
66+
path->points, trajectory->compute(*stop_point).point.pose,
67+
planner_data_->current_odometry->pose, planner_data_->current_odometry->pose,
68+
tier4_planning_msgs::msg::PlanningFactor::STOP, tier4_planning_msgs::msg::SafetyFactorArray{},
69+
true /*is_driving_forward*/, 0.0, 0.0 /*shift distance*/, "stopline");
6670

6771
updateStateAndStoppedTime(
6872
&state_, &stopped_time_, clock_->now(), *stop_point - ego_s, planner_data_->isVehicleStopped());
@@ -152,24 +156,6 @@ void StopLineModule::updateStateAndStoppedTime(
152156
}
153157
}
154158

155-
void StopLineModule::updateVelocityFactor(
156-
autoware::motion_utils::VelocityFactorInterface * velocity_factor, const State & state,
157-
const double & distance_to_stop_point)
158-
{
159-
switch (state) {
160-
case State::APPROACH: {
161-
velocity_factor->set(distance_to_stop_point, VelocityFactor::APPROACHING);
162-
break;
163-
}
164-
case State::STOPPED: {
165-
velocity_factor->set(distance_to_stop_point, VelocityFactor::STOPPED);
166-
break;
167-
}
168-
case State::START:
169-
break;
170-
}
171-
}
172-
173159
void StopLineModule::updateDebugData(
174160
DebugData * debug_data, const geometry_msgs::msg::Pose & stop_pose, const State & state) const
175161
{

planning/behavior_velocity_planner/autoware_behavior_velocity_stop_line_module/src/scene.hpp

-5
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,6 @@
1818

1919
#include "autoware/behavior_velocity_planner_common/scene_module_interface.hpp"
2020
#include "autoware/behavior_velocity_planner_common/utilization/util.hpp"
21-
#include "autoware/motion_utils/factor/velocity_factor_interface.hpp"
2221
#include "autoware/trajectory/path_point_with_lane_id.hpp"
2322

2423
#include <Eigen/Core>
@@ -98,10 +97,6 @@ class StopLineModule : public SceneModuleInterface
9897
State * state, std::optional<rclcpp::Time> * stopped_time, const rclcpp::Time & now,
9998
const double & distance_to_stop_point, const bool & is_vehicle_stopped) const;
10099

101-
static void updateVelocityFactor(
102-
autoware::motion_utils::VelocityFactorInterface * velocity_factor, const State & state,
103-
const double & distance_to_stop_point);
104-
105100
void updateDebugData(
106101
DebugData * debug_data, const geometry_msgs::msg::Pose & stop_pose, const State & state) const;
107102

planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/manager.cpp

-12
Original file line numberDiff line numberDiff line change
@@ -53,24 +53,13 @@ void TrafficLightModuleManager::modifyPathVelocity(tier4_planning_msgs::msg::Pat
5353

5454
autoware_perception_msgs::msg::TrafficLightGroup tl_state;
5555

56-
autoware_adapi_v1_msgs::msg::VelocityFactorArray velocity_factor_array;
57-
velocity_factor_array.header.frame_id = "map";
58-
velocity_factor_array.header.stamp = clock_->now();
59-
6056
nearest_ref_stop_path_point_index_ = static_cast<int>(path->points.size() - 1);
6157
for (const auto & scene_module : scene_modules_) {
6258
std::shared_ptr<TrafficLightModule> traffic_light_scene_module(
6359
std::dynamic_pointer_cast<TrafficLightModule>(scene_module));
64-
traffic_light_scene_module->resetVelocityFactor();
6560
traffic_light_scene_module->setPlannerData(planner_data_);
6661
traffic_light_scene_module->modifyPathVelocity(path);
6762

68-
// The velocity factor must be called after modifyPathVelocity.
69-
const auto velocity_factor = traffic_light_scene_module->getVelocityFactor();
70-
if (velocity_factor.behavior != PlanningBehavior::UNKNOWN) {
71-
velocity_factor_array.factors.emplace_back(velocity_factor);
72-
}
73-
7463
if (
7564
traffic_light_scene_module->getFirstRefStopPathPointIndex() <
7665
nearest_ref_stop_path_point_index_) {
@@ -88,7 +77,6 @@ void TrafficLightModuleManager::modifyPathVelocity(tier4_planning_msgs::msg::Pat
8877
virtual_wall_marker_creator_.add_virtual_walls(
8978
traffic_light_scene_module->createVirtualWalls());
9079
}
91-
pub_velocity_factor_->publish(velocity_factor_array);
9280
pub_debug_->publish(debug_marker_array);
9381
pub_virtual_wall_->publish(virtual_wall_marker_creator_.create_markers(clock_->now()));
9482
pub_tl_state_->publish(tl_state);

planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/scene.cpp

+4-3
Original file line numberDiff line numberDiff line change
@@ -54,7 +54,6 @@ TrafficLightModule::TrafficLightModule(
5454
debug_data_(),
5555
is_prev_state_stop_(false)
5656
{
57-
velocity_factor_.init(PlanningBehavior::TRAFFIC_SIGNAL);
5857
planner_param_ = planner_param;
5958
}
6059

@@ -293,9 +292,11 @@ tier4_planning_msgs::msg::PathWithLaneId TrafficLightModule::insertStopPose(
293292
size_t insert_index = insert_target_point_idx;
294293
planning_utils::insertVelocity(modified_path, target_point_with_lane_id, 0.0, insert_index);
295294

296-
velocity_factor_.set(
295+
planning_factor_interface_->add(
297296
modified_path.points, planner_data_->current_odometry->pose,
298-
target_point_with_lane_id.point.pose, VelocityFactor::UNKNOWN);
297+
target_point_with_lane_id.point.pose, target_point_with_lane_id.point.pose,
298+
tier4_planning_msgs::msg::PlanningFactor::STOP, tier4_planning_msgs::msg::SafetyFactorArray{},
299+
true /*is_driving_forward*/, 0.0, 0.0 /*shift distance*/, "");
299300

300301
return modified_path;
301302
}

planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.cpp

+8-7
Original file line numberDiff line numberDiff line change
@@ -48,8 +48,6 @@ VirtualTrafficLightModule::VirtualTrafficLightModule(
4848
lane_(lane),
4949
planner_param_(planner_param)
5050
{
51-
velocity_factor_.init(PlanningBehavior::VIRTUAL_TRAFFIC_LIGHT);
52-
5351
// Get map data
5452
const auto instrument = reg_elem_.getVirtualTrafficLight();
5553
const auto instrument_bottom_line = toAutowarePoints(instrument);
@@ -420,9 +418,10 @@ void VirtualTrafficLightModule::insertStopVelocityAtStopLine(
420418
}
421419

422420
// Set StopReason
423-
velocity_factor_.set(
424-
path->points, planner_data_->current_odometry->pose, stop_pose, VelocityFactor::UNKNOWN,
425-
command_.type);
421+
planning_factor_interface_->add(
422+
path->points, planner_data_->current_odometry->pose, stop_pose, stop_pose,
423+
tier4_planning_msgs::msg::PlanningFactor::STOP, tier4_planning_msgs::msg::SafetyFactorArray{},
424+
true /*is_driving_forward*/, 0.0, 0.0 /*shift distance*/, "");
426425

427426
// Set data for visualization
428427
module_data_.stop_head_pose_at_stop_line =
@@ -453,8 +452,10 @@ void VirtualTrafficLightModule::insertStopVelocityAtEndLine(
453452
}
454453

455454
// Set StopReason
456-
velocity_factor_.set(
457-
path->points, planner_data_->current_odometry->pose, stop_pose, VelocityFactor::UNKNOWN);
455+
planning_factor_interface_->add(
456+
path->points, planner_data_->current_odometry->pose, stop_pose, stop_pose,
457+
tier4_planning_msgs::msg::PlanningFactor::STOP, tier4_planning_msgs::msg::SafetyFactorArray{},
458+
true /*is_driving_forward*/, 0.0, 0.0 /*shift distance*/, "");
458459

459460
// Set data for visualization
460461
module_data_.stop_head_pose_at_end_line =

planning/behavior_velocity_planner/autoware_behavior_velocity_virtual_traffic_light_module/src/scene.hpp

-4
Original file line numberDiff line numberDiff line change
@@ -113,10 +113,6 @@ class VirtualTrafficLightModule : public SceneModuleInterface
113113

114114
void updateInfrastructureCommand();
115115

116-
void setVelocityFactor(
117-
const geometry_msgs::msg::Pose & stop_pose,
118-
autoware_adapi_v1_msgs::msg::VelocityFactor * velocity_factor);
119-
120116
std::optional<size_t> getPathIndexOfFirstEndLine();
121117

122118
bool isBeforeStartLine(const size_t end_line_idx);

0 commit comments

Comments
 (0)